diff --git a/README.md b/README.md index 718da785a..c852e18a9 100644 --- a/README.md +++ b/README.md @@ -1,3 +1,81 @@ +# Starting ROS2 Demo + +## Install foxy version of ros2_control or check its sourc + +## Checkout repositories +**Note**: you can use relese of the ros2_control repository + + ``` + git clone https://github.com/ros-controls/ros2_control.git + ``` + +Checkout changed version of `JointTrajectoryController` + ``` + git clone https://github.com/ros-controls/ros2_controllers.git + cd ros2_controllers + git remote add denis https://github.com/destogl/ros2_controllers.git + git fetch denis + git checkout denis/jtc_versions + ``` + +Checkout changed version of ros2_demos repository + ``` + git clone -b add_demo_nodes https://github.com/ros-controls/ros2_control_demos.git + ``` + +Checkout KUKA demo driver and changed `kuka_experimental` repositories + ``` + git clone https://github.com/dignakov/kuka_experimental.git + git clone https://github.com/dignakov/ros2_control_demo_drivers.git + ``` +**Attention**: remove `ros2_control_abb_demo_driver` package for `ros2_control_demo_drivers` if needed. + +Compile everything using: + ``` + colcon build --symlink-install + ``` + +## Starting Robot +1. In a terminal start ros2_control framework with KUKA RSI system hardware: + ``` + ros2 launch kuka_kr5_support kr5_rsi.launch.py + ``` + +2. In the second terminal start KUKA RSI simulator: + ``` + ros2 run kuka_rsi_simulator kuka_rsi_simulator + ``` + +3. In the third terminal start `rviz2`. + And add RobotModel from the `/robot_description` topic. + You can also just open rviz config from `kuka_kr5_support`/config/test_controllers.rviz + +4. Follow the test case for one of the controllers. + + +### Test with ForwardCommandController (it will not work on the hardware if positions are not interpolated) +1. Load and start controllers: + ``` + ros2 control load_start_controller joint_state_controller + ros2 control load_start_controller forward_position_controller + ``` +2. Start a test node which sends commmands in a loop to the controller: + ``` + ros2 launch kuka_kr5_support test_forward_position_controller.launch.py + ``` + +### Test with JointTrajectoryController +1. Load and start controllers: + ``` + ros2 control load_start_controller joint_state_controller + ros2 control load_start_controller position_trajectory_controller + ``` + +2. Start a test node which sends commmands in a loop to the controller: + ``` + ros2 launch kuka_kr5_support test_position_trajectory_controller.launch.py + ``` + # Kuka experimental [![Build Status](http://build.ros.org/job/Kdev__kuka_experimental__ubuntu_xenial_amd64/badge/icon)](http://build.ros.org/job/Kdev__kuka_experimental__ubuntu_xenial_amd64) diff --git a/kuka_experimental/package.xml b/kuka_experimental/package.xml index 811f572ff..285befb4f 100644 --- a/kuka_experimental/package.xml +++ b/kuka_experimental/package.xml @@ -13,6 +13,7 @@ ament_cmake + kuka_kr5_support kuka_kr6_support kuka_resources diff --git a/kuka_kr5_support/CMakeLists.txt b/kuka_kr5_support/CMakeLists.txt new file mode 100644 index 000000000..d6989511a --- /dev/null +++ b/kuka_kr5_support/CMakeLists.txt @@ -0,0 +1,14 @@ +cmake_minimum_required(VERSION 3.5) + +project(kuka_kr5_support) + +find_package(ament_cmake REQUIRED) + +if (CATKIN_ENABLE_TESTING) +endif() + +install(DIRECTORY config launch meshes urdf + DESTINATION share/${PROJECT_NAME} +) + +ament_package() diff --git a/kuka_kr5_support/config/hardware_controllers.yaml b/kuka_kr5_support/config/hardware_controllers.yaml new file mode 100644 index 000000000..17f809c3a --- /dev/null +++ b/kuka_kr5_support/config/hardware_controllers.yaml @@ -0,0 +1,41 @@ +controller_manager: + ros__parameters: + update_rate: 250 # Hz + + joint_state_controller: + type: joint_state_controller/JointStateController + + forward_position_controller: + type: forward_command_controller/ForwardCommandController + + position_trajectory_controller: + type: joint_trajectory_controller/JointTrajectoryController + +forward_position_controller: + ros__parameters: + joints: + - joint_a1 + - joint_a2 + - joint_a3 + - joint_a4 + - joint_a5 + - joint_a6 + interface_name: position + +position_trajectory_controller: + ros__parameters: + joints: + - joint_a1 + - joint_a2 + - joint_a3 + - joint_a4 + - joint_a5 + - joint_a6 + + state_publish_rate: 50.0 # Defaults to 50 + action_monitor_rate: 20.0 # Defaults to 20 + + allow_partial_joints_goal: false # Defaults to false + constraints: + stopped_velocity_tolerance: 0.01 # Defaults to 0.01 + goal_time: 0.0 # Defaults to 0.0 (start immediatelly) diff --git a/kuka_kr5_support/config/joint_names_kr5.yaml b/kuka_kr5_support/config/joint_names_kr5.yaml new file mode 100644 index 000000000..1a23ced85 --- /dev/null +++ b/kuka_kr5_support/config/joint_names_kr5.yaml @@ -0,0 +1 @@ +controller_joint_names: ['joint_a1', 'joint_a2', 'joint_a3', 'joint_a4', 'joint_a5', 'joint_a6'] diff --git a/kuka_kr5_support/config/test_controllers.rviz b/kuka_kr5_support/config/test_controllers.rviz new file mode 100644 index 000000000..aa5caf7a0 --- /dev/null +++ b/kuka_kr5_support/config/test_controllers.rviz @@ -0,0 +1,190 @@ +Panels: + - Class: rviz_common/Displays + Help Height: 87 + Name: Displays + Property Tree Widget: + Expanded: + - /Global Options1 + - /Status1 + - /RobotModel1 + Splitter Ratio: 0.5 + Tree Height: 780 + - Class: rviz_common/Selection + Name: Selection + - Class: rviz_common/Tool Properties + Expanded: + - /2D Goal Pose1 + - /Publish Point1 + Name: Tool Properties + Splitter Ratio: 0.5886790156364441 + - Class: rviz_common/Views + Expanded: + - /Current View1 + Name: Views + Splitter Ratio: 0.5 +Visualization Manager: + Class: "" + Displays: + - Alpha: 0.5 + Cell Size: 1 + Class: rviz_default_plugins/Grid + Color: 160; 160; 164 + Enabled: true + Line Style: + Line Width: 0.029999999329447746 + Value: Lines + Name: Grid + Normal Cell Count: 0 + Offset: + X: 0 + Y: 0 + Z: 0 + Plane: XY + Plane Cell Count: 10 + Reference Frame: + Value: true + - Alpha: 1 + Class: rviz_default_plugins/RobotModel + Collision Enabled: false + Description File: "" + Description Source: Topic + Description Topic: + Depth: 5 + Durability Policy: Volatile + History Policy: Keep Last + Reliability Policy: Reliable + Value: /robot_description + Enabled: true + Links: + All Links Enabled: true + Expand Joint Details: false + Expand Link Details: false + Expand Tree: false + Link Tree Style: Links in Alphabetic Order + base: + Alpha: 1 + Show Axes: false + Show Trail: false + base_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + link_1: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + link_2: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + link_3: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + link_4: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + link_5: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + link_6: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + tool0: + Alpha: 1 + Show Axes: false + Show Trail: false + Name: RobotModel + TF Prefix: "" + Update Interval: 0 + Value: true + Visual Enabled: true + Enabled: true + Global Options: + Background Color: 48; 48; 48 + Fixed Frame: base + Frame Rate: 30 + Name: root + Tools: + - Class: rviz_default_plugins/Interact + Hide Inactive Objects: true + - Class: rviz_default_plugins/MoveCamera + - Class: rviz_default_plugins/Select + - Class: rviz_default_plugins/FocusCamera + - Class: rviz_default_plugins/Measure + Line color: 128; 128; 0 + - Class: rviz_default_plugins/SetInitialPose + Topic: + Depth: 5 + Durability Policy: Volatile + History Policy: Keep Last + Reliability Policy: Reliable + Value: /initialpose + - Class: rviz_default_plugins/SetGoal + Topic: + Depth: 5 + Durability Policy: Volatile + History Policy: Keep Last + Reliability Policy: Reliable + Value: /goal_pose + - Class: rviz_default_plugins/PublishPoint + Single click: true + Topic: + Depth: 5 + Durability Policy: Volatile + History Policy: Keep Last + Reliability Policy: Reliable + Value: /clicked_point + Transformation: + Current: + Class: rviz_default_plugins/TF + Value: true + Views: + Current: + Class: rviz_default_plugins/Orbit + Distance: 2.50931453704834 + Enable Stereo Rendering: + Stereo Eye Separation: 0.05999999865889549 + Stereo Focal Distance: 1 + Swap Stereo Eyes: false + Value: false + Focal Point: + X: 0.41824325919151306 + Y: -0.2059020698070526 + Z: 0.9586235284805298 + Focal Shape Fixed Size: true + Focal Shape Size: 0.05000000074505806 + Invert Z Axis: false + Name: Current View + Near Clip Distance: 0.009999999776482582 + Pitch: 0.5403985381126404 + Target Frame: + Value: Orbit (rviz) + Yaw: 4.988577365875244 + Saved: ~ +Window Geometry: + Displays: + collapsed: false + Height: 1051 + Hide Left Dock: false + Hide Right Dock: false + QMainWindow State: 000000ff00000000fd00000004000000000000016a000003b0fc0200000008fb0000001200530065006c0065006300740069006f006e00000001e10000009b0000007901000003fb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000001ed000001df00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c0061007900730100000044000003b0000000fd01000003fb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c000002610000000100000110000003b0fc0200000003fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a005600690065007700730100000044000003b0000000d301000003fb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e10000019700000003000004420000003efc0100000002fb0000000800540069006d00650100000000000004420000000000000000fb0000000800540069006d0065010000000000000450000000000000000000000504000003b000000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000 + Selection: + collapsed: false + Tool Properties: + collapsed: false + Views: + collapsed: false + Width: 1920 + X: 5120 + Y: 180 diff --git a/kuka_kr5_support/config/test_forward_position_publisher.yaml b/kuka_kr5_support/config/test_forward_position_publisher.yaml new file mode 100644 index 000000000..b1866bf55 --- /dev/null +++ b/kuka_kr5_support/config/test_forward_position_publisher.yaml @@ -0,0 +1,10 @@ +publisher_forward_position_controller: + ros__parameters: + + wait_sec_between_publish: 1 + + goal_names: ["pos1", "pos2", "pos3", "pos4"] + pos1: [0.0, -1.571, 0.758, -0.758, 0.758, 0.0] + pos2: [0.0, -1.571, 1.571, 0.0, 1.571, 0.0] + pos3: [0.0, -1.571, 2.329, 0.758, 0.758, 0.0] + pos4: [0.0, -1.571, 1.571, 0.0, 1.571, 0.0] diff --git a/kuka_kr5_support/config/test_position_trajectory_publisher.yaml b/kuka_kr5_support/config/test_position_trajectory_publisher.yaml new file mode 100644 index 000000000..2023f900e --- /dev/null +++ b/kuka_kr5_support/config/test_position_trajectory_publisher.yaml @@ -0,0 +1,18 @@ +publisher_joint_trajectory_controller: + ros__parameters: + + controller_name: position_trajectory_controller + + goal_names: ["pos1", "pos2", "pos3", "pos4"] + pos1: [0.0, -1.571, 0.758, -0.758, 0.758, 0.0] + pos2: [0.0, -1.571, 1.571, 0.0, 1.571, 0.0] + pos3: [0.0, -1.571, 2.329, 0.758, 0.758, 0.0] + pos4: [0.0, -1.571, 1.571, 0.0, 1.571, 0.0] + + joints: + - joint_a1 + - joint_a2 + - joint_a3 + - joint_a4 + - joint_a5 + - joint_a6 diff --git a/kuka_kr5_support/launch/kr5_rsi.launch.py b/kuka_kr5_support/launch/kr5_rsi.launch.py new file mode 100644 index 000000000..2f0aa1e03 --- /dev/null +++ b/kuka_kr5_support/launch/kr5_rsi.launch.py @@ -0,0 +1,58 @@ +# Copyright 2020 ROS2-Control Development Team (2020) +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. + +import os + +from ament_index_python.packages import get_package_share_directory + +from launch import LaunchDescription +from launch_ros.actions import Node + +import xacro + + +def generate_launch_description(): + + # Get URDF via xacro + robot_description_path = os.path.join( + get_package_share_directory('kuka_kr5_support'), + 'urdf', + 'kr5_arc_ros2.xacro') + robot_description_config = xacro.process_file(robot_description_path, + mappings={'rsi_ip': '127.0.0.1'}) + robot_description = {'robot_description': robot_description_config.toxml()} + + kuka_controllers = os.path.join( + get_package_share_directory('kuka_kr5_support'), + 'config', + 'hardware_controllers.yaml' + ) + + return LaunchDescription([ + Node( + package='controller_manager', + executable='ros2_control_node', + parameters=[robot_description, kuka_controllers], + output={ + 'stdout': 'screen', + 'stderr': 'screen', + }, + ), + Node( + package='robot_state_publisher', + executable='robot_state_publisher', + output='both', + parameters=[robot_description] + ) + ]) diff --git a/kuka_kr5_support/launch/load_kr5_arc.launch b/kuka_kr5_support/launch/load_kr5_arc.launch new file mode 100644 index 000000000..261c87fe1 --- /dev/null +++ b/kuka_kr5_support/launch/load_kr5_arc.launch @@ -0,0 +1,5 @@ + + + + + diff --git a/kuka_kr5_support/launch/test_forward_position_controller.launch.py b/kuka_kr5_support/launch/test_forward_position_controller.launch.py new file mode 100644 index 000000000..a3958997b --- /dev/null +++ b/kuka_kr5_support/launch/test_forward_position_controller.launch.py @@ -0,0 +1,42 @@ +# Copyright 2021 Stogl Robotics Consulting +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. + +import os + +from ament_index_python.packages import get_package_share_directory + +from launch import LaunchDescription +from launch_ros.actions import Node + + +def generate_launch_description(): + + publisher_config = os.path.join( + get_package_share_directory('kuka_kr5_support'), + 'config', + 'test_forward_position_publisher.yaml' + ) + + return LaunchDescription([ + Node( + package='ros2_control_test_nodes', + executable='publisher_forward_position_controller', + parameters=[publisher_config], + output={ + 'stdout': 'screen', + 'stderr': 'screen', + }, + ) + + ]) diff --git a/kuka_kr5_support/launch/test_kr5_arc.launch b/kuka_kr5_support/launch/test_kr5_arc.launch new file mode 100644 index 000000000..c0ac06546 --- /dev/null +++ b/kuka_kr5_support/launch/test_kr5_arc.launch @@ -0,0 +1,9 @@ + + + + + + + + + diff --git a/kuka_kr5_support/launch/test_position_trajectory_controller.launch.py b/kuka_kr5_support/launch/test_position_trajectory_controller.launch.py new file mode 100644 index 000000000..9cc416c58 --- /dev/null +++ b/kuka_kr5_support/launch/test_position_trajectory_controller.launch.py @@ -0,0 +1,42 @@ +# Copyright 2021 Stogl Robotics Consulting +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. + +import os + +from ament_index_python.packages import get_package_share_directory + +from launch import LaunchDescription +from launch_ros.actions import Node + + +def generate_launch_description(): + + publisher_config = os.path.join( + get_package_share_directory('kuka_kr5_support'), + 'config', + 'test_position_trajectory_publisher.yaml' + ) + + return LaunchDescription([ + Node( + package='ros2_control_test_nodes', + executable='publisher_joint_trajectory_controller', + parameters=[publisher_config], + output={ + 'stdout': 'screen', + 'stderr': 'screen', + }, + ) + + ]) diff --git a/kuka_kr5_support/meshes/kr5_arc/collision/base_link.stl b/kuka_kr5_support/meshes/kr5_arc/collision/base_link.stl new file mode 100644 index 000000000..3497f8a78 Binary files /dev/null and b/kuka_kr5_support/meshes/kr5_arc/collision/base_link.stl differ diff --git a/kuka_kr5_support/meshes/kr5_arc/collision/link_1.stl b/kuka_kr5_support/meshes/kr5_arc/collision/link_1.stl new file mode 100644 index 000000000..ec226170b Binary files /dev/null and b/kuka_kr5_support/meshes/kr5_arc/collision/link_1.stl differ diff --git a/kuka_kr5_support/meshes/kr5_arc/collision/link_2.stl b/kuka_kr5_support/meshes/kr5_arc/collision/link_2.stl new file mode 100644 index 000000000..dcf0fd9e0 Binary files /dev/null and b/kuka_kr5_support/meshes/kr5_arc/collision/link_2.stl differ diff --git a/kuka_kr5_support/meshes/kr5_arc/collision/link_3.stl b/kuka_kr5_support/meshes/kr5_arc/collision/link_3.stl new file mode 100644 index 000000000..d5d41893b Binary files /dev/null and b/kuka_kr5_support/meshes/kr5_arc/collision/link_3.stl differ diff --git a/kuka_kr5_support/meshes/kr5_arc/collision/link_4.stl b/kuka_kr5_support/meshes/kr5_arc/collision/link_4.stl new file mode 100644 index 000000000..43be9ede4 Binary files /dev/null and b/kuka_kr5_support/meshes/kr5_arc/collision/link_4.stl differ diff --git a/kuka_kr5_support/meshes/kr5_arc/collision/link_5.stl b/kuka_kr5_support/meshes/kr5_arc/collision/link_5.stl new file mode 100644 index 000000000..deaf7f307 Binary files /dev/null and b/kuka_kr5_support/meshes/kr5_arc/collision/link_5.stl differ diff --git a/kuka_kr5_support/meshes/kr5_arc/collision/link_6.stl b/kuka_kr5_support/meshes/kr5_arc/collision/link_6.stl new file mode 100644 index 000000000..dd3db19d6 Binary files /dev/null and b/kuka_kr5_support/meshes/kr5_arc/collision/link_6.stl differ diff --git a/kuka_kr5_support/meshes/kr5_arc/visual/base_link.dae b/kuka_kr5_support/meshes/kr5_arc/visual/base_link.dae new file mode 100644 index 000000000..188a15746 --- /dev/null +++ b/kuka_kr5_support/meshes/kr5_arc/visual/base_link.dae @@ -0,0 +1,423 @@ + + + + + Blender User + Blender 2.79.0 commit date:2017-09-11, commit time:10:43, hash:5bd8ac9abfa + + 2017-11-10T19:57:49 + 2017-11-10T19:57:49 + + Z_UP + + + + + + + 49.13434 + 1.777778 + 0.1 + 100 + + + + + + 0 + 0 + 0 + + + + + + + + + 1 1 1 + 1 + 0 + 0.00111109 + + + + + 0 + 0 + 8192 + 1 + 1 + 1 + 1 + 0 + 0 + 0 + 1 + 29.99998 + 75 + 0.15 + 1 + 0 + 1 + 2 + 1.000799 + 30.002 + 1 + 3 + 0.04999995 + 2880 + 3 + 1 + 0 + 0 + 2 + 1 + 1 + 1 + 0 + 1 + 0.1 + 0.1 + 1 + 0.000999987 + 1 + 0 + 0 + 1 + 1 + 1 + 1 + 1 + 1 + 1 + 2 + 1 + 1 + 1 + 1 + 0 + + + + + + + + + + + + 0 0 0 1 + + + 0 0 0 1 + + + 0.6 0.6 0.6 1 + + + 0.5 0.5 0.5 1 + + + 0 + + + 1 1 1 1 + + + 1 + + + + + + + + + + + 0 0 0 1 + + + 0 0 0 1 + + + 1 0.4 0 1 + + + 0.5 0.5 0.5 1 + + + 0 + + + 1 1 1 1 + + + 1 + + + + + + + + + + + 0 0 0 1 + + + 0 0 0 1 + + + 0.09803922 0.09803922 0.09803922 1 + + + 0.5 0.5 0.5 1 + + + 0 + + + 1 1 1 1 + + + 1 + + + + + + + + + + + 0 0 0 1 + + + 0 0 0 1 + + + 0 0 0 1 + + + 0.5 0.5 0.5 1 + + + 0 + + + 1 1 1 1 + + + 1 + + + + + + + + + + + + + + + + + + + + + + + + + -0.1946099 -0.1335394 0.1829695 -0.1951692 -0.134263 0.1830643 -0.1942508 -0.1349826 0.1845835 -0.1935254 -0.1344091 0.1846882 -0.19278 -0.1334952 0.1835007 -0.1936248 -0.1331378 0.1827182 -0.1941552 -0.1330192 0.1817438 -0.1947683 -0.1332847 0.1821466 -0.1942222 -0.1368295 0.1850155 -0.1934798 -0.1380916 0.1859267 -0.1914339 -0.1368874 0.1858472 -0.1916476 -0.1379311 0.1860887 -0.1924203 -0.1379884 0.1862321 -0.19499 -0.1352357 0.1836745 -0.1936994 -0.1363848 0.1855447 -0.1928693 -0.1360777 0.1858321 -0.1919212 -0.135895 0.1857072 -0.1919143 -0.1348826 0.1850098 -0.1926132 -0.1340973 0.1844742 -0.1942393 -0.2072923 0.1849815 -0.1936399 -0.206624 0.1857584 -0.1928176 -0.2067812 0.1861459 -0.1924722 -0.2060338 0.1862292 -0.1916564 -0.2059831 0.1860992 -0.1264024 -0.138 0.1486862 -0.1264648 -0.1368886 0.1485775 -0.1266492 -0.1358304 0.1482562 -0.1269456 -0.1348819 0.1477394 -0.127339 -0.1340913 0.1470537 -0.127811 -0.1334954 0.1462308 -0.1283373 -0.1331253 0.1453135 -0.1288906 -0.133 0.1443489 -0.26512 -0.1343317 0.06121486 -0.2647777 -0.1335958 0.0608884 -0.2639866 -0.1330453 0.06046259 -0.2029846 -0.1935 0.1697314 -0.2029846 -0.1495 0.1697314 -0.2666245 -0.2072189 0.05880314 -0.2658655 -0.2087712 0.06012278 -0.2626964 -0.1935 0.06564199 -0.2627744 -0.1867855 0.06550604 -0.2666402 -0.1367833 0.05877125 -0.2627909 -0.1575159 0.06547719 -0.2626964 -0.1562896 0.06564199 -0.2626964 -0.1495 0.06564199 -0.2658696 -0.135267 0.06012141 -0.1949917 -0.2087373 0.1836738 -0.1939319 -0.2083768 0.1851391 -0.1931461 -0.2088285 0.1853495 -0.1916179 -0.2081694 0.1855265 -0.1917343 -0.2071003 0.1859995 -0.1955575 -0.209668 0.1824758 -0.1933059 -0.2108746 0.182584 -0.1943621 -0.2109563 0.1818421 -0.1946297 -0.2094849 0.1839229 -0.1951028 -0.2104042 0.1823452 -0.1939765 -0.2101473 0.1839021 -0.1931135 -0.2105165 0.1836113 -0.1923083 -0.2099092 0.184323 -0.1922122 -0.2090969 0.1851731 -0.1264024 -0.2059995 0.1486862 -0.1985541 -0.133 0.02291184 -0.2668902 -0.1372018 0.05697095 -0.2669919 -0.1373981 0.05786329 -0.2662756 -0.1371362 0.05609166 -0.2657646 -0.1358306 0.05627417 -0.2667807 -0.1379945 0.0566141 -0.2640767 -0.1331254 0.05921661 -0.2659008 -0.1345151 0.05968356 -0.265553 -0.1338527 0.05913013 -0.2648768 -0.1334894 0.05853158 -0.2650743 -0.1340908 0.05747759 -0.2665984 -0.1356232 0.05846732 -0.2663833 -0.1351715 0.05768275 -0.2657599 -0.1349031 0.05696576 -0.2654318 -0.2097371 0.06058293 -0.2650676 -0.2104606 0.06014788 -0.2644374 -0.2107152 0.06069993 -0.2642586 -0.2109174 0.05960792 -0.2662797 -0.2090173 0.05902302 -0.266004 -0.2095909 0.058344 -0.2646025 -0.2105048 0.05829995 -0.2669958 -0.2058984 0.05794495 -0.2659486 -0.2071126 0.05595338 -0.2664641 -0.2059434 0.05615496 -0.2668311 -0.2076151 0.05806177 -0.2669636 -0.2060113 0.0570783 -0.2666602 -0.2079223 0.05720013 -0.2660693 -0.2080994 0.05643546 -0.2654682 -0.2091174 0.05679088 -0.2653588 -0.2099027 0.05766445 -0.2808539 -0.156058 0.0761252 -0.2878091 -0.1579711 0.07987016 -0.287635 -0.1562464 0.07999056 -0.2829586 -0.1545593 0.07797288 -0.2873175 -0.1545706 0.08052116 -0.2868502 -0.1531018 0.08138716 -0.28666 -0.1755404 0.07916098 -0.2878046 -0.1859872 0.07985872 -0.2877426 -0.1794176 0.07981652 -0.286328 -0.1715 0.07897061 -0.2877183 -0.1636669 0.07978767 -0.2865408 -0.1682203 0.0790928 -0.282564 -0.1892215 0.07762777 -0.2873236 -0.1894045 0.08050972 -0.2876384 -0.1877327 0.07998681 -0.2808539 -0.187942 0.0761252 -0.2808539 -0.1935 0.07612526 -0.2208539 -0.1935 0.1800483 -0.2691552 -0.1935 0.196388 -0.3191552 -0.1935 0.1097854 -0.246764 -0.1935 0.1221178 -0.2480217 -0.1935 0.1216979 -0.2498908 -0.1935 0.1216047 -0.2456434 -0.1935 0.1228263 -0.2442689 -0.1935 0.1244235 -0.2518718 -0.1935 0.1223236 -0.2529318 -0.1935 0.1231202 -0.2537704 -0.1935 0.1241472 -0.2543388 -0.1935 0.1253451 -0.254604 -0.1935 0.1266441 -0.2545506 -0.1935 0.127969 -0.2436931 -0.1935 0.1262045 -0.2436397 -0.1935 0.1275293 -0.2439049 -0.1935 0.1288284 -0.2444733 -0.1935 0.1300263 -0.2453117 -0.1935 0.1310534 -0.2475916 -0.1935 0.1323696 -0.2463718 -0.1935 0.1318499 -0.2489004 -0.1935 0.1325823 -0.250222 -0.1935 0.1324756 -0.2514796 -0.1935 0.1320558 -0.2526003 -0.1935 0.1313471 -0.2541817 -0.1935 0.1292425 -0.2535188 -0.1935 0.1303909 -0.2208539 -0.1495 0.1800483 -0.2514796 -0.1495 0.1320558 -0.2691552 -0.1495 0.196388 -0.2494472 -0.1495 0.1326129 -0.2526003 -0.1495 0.1313471 -0.2475916 -0.1495 0.1323696 -0.2535188 -0.1495 0.1303909 -0.2463718 -0.1495 0.1318499 -0.2453117 -0.1495 0.1310534 -0.2444733 -0.1495 0.1300263 -0.3191552 -0.1495 0.1097854 -0.2541817 -0.1495 0.1292425 -0.2545506 -0.1495 0.127969 -0.254604 -0.1495 0.1266441 -0.2439049 -0.1495 0.1288284 -0.2543388 -0.1495 0.1253451 -0.2436397 -0.1495 0.1275293 -0.2537704 -0.1495 0.1241472 -0.2436931 -0.1495 0.1262045 -0.2443891 -0.1495 0.1242153 -0.2808539 -0.1495 0.0761252 -0.2529318 -0.1495 0.1231202 -0.2518718 -0.1495 0.1223236 -0.250652 -0.1495 0.1218039 -0.2456434 -0.1495 0.1228263 -0.246764 -0.1495 0.1221178 -0.2480217 -0.1495 0.1216979 -0.2493433 -0.1495 0.1215912 -0.1264648 -0.2071114 0.1485775 -0.1266492 -0.2081694 0.1482562 -0.1269456 -0.2091182 0.1477393 -0.127339 -0.2099087 0.1470537 -0.127811 -0.2105045 0.1462308 -0.1283373 -0.2108746 0.1453135 -0.1288906 -0.211 0.1443489 -0.2009797 -0.1368876 0.01868361 -0.2010419 -0.1380003 0.01857489 -0.2007956 -0.1358308 0.01900428 -0.200499 -0.1348823 0.01952129 -0.2001053 -0.1340907 0.0202077 -0.1996336 -0.1334952 0.02103006 -0.1991078 -0.1331254 0.02194654 -0.3091074 -0.1552244 0.1009552 -0.3117401 -0.1584182 0.103269 -0.3059838 -0.1529453 0.09821009 -0.302545 -0.1517094 0.09518796 -0.2989843 -0.1515861 0.09205871 -0.2873494 -0.1901245 0.08183342 -0.2922934 -0.1883583 0.0861786 -0.2871406 -0.1906445 0.08164709 -0.2895393 -0.1853511 0.08375823 -0.3137341 -0.1623477 0.1050212 -0.2955018 -0.1904179 0.08899825 -0.2868671 -0.1908969 0.08140069 -0.3149771 -0.1667914 0.1061137 -0.3153994 -0.1715 0.1064848 -0.2873583 -0.153994 0.08184278 -0.2922934 -0.1546417 0.0861786 -0.2871888 -0.1534163 0.08168935 -0.2895393 -0.1576489 0.08375823 -0.2873945 -0.1614348 0.08187335 -0.3059838 -0.1900545 0.09821009 -0.302545 -0.1912904 0.09518796 -0.2955018 -0.1525821 0.08899825 -0.3091074 -0.1877756 0.1009552 -0.3117401 -0.1845816 0.103269 -0.3137341 -0.1806523 0.1050212 -0.3149771 -0.1762084 0.1061137 -0.2989843 -0.1914139 0.09205871 -0.2873945 -0.1815652 0.08187335 -0.2876323 -0.1547415 0.0810467 -0.2878302 -0.1567989 0.08111763 -0.2880365 -0.158092 0.08057034 -0.287916 -0.156349 0.08049905 -0.2876642 -0.155636 0.08140319 -0.2880529 -0.1620196 0.08061295 -0.309537 -0.1582809 0.06017881 -0.3122592 -0.155071 0.0625624 -0.3261438 -0.1901381 0.07498663 -0.3224378 -0.1913597 0.0718128 -0.3074668 -0.1622209 0.05840831 -0.3292273 -0.1879904 0.0775423 -0.3061963 -0.1667236 0.05728054 -0.3320023 -0.1847564 0.07992196 -0.3340575 -0.1807603 0.08177912 -0.3352541 -0.176558 0.08291184 -0.3352034 -0.1715 0.08395034 -0.3353243 -0.1667681 0.08293402 -0.3340497 -0.1621944 0.08173447 -0.3319247 -0.1581687 0.07994383 -0.3287144 -0.1550403 0.07824766 -0.326111 -0.1528421 0.07485479 -0.3224433 -0.1516396 0.07161849 -0.306199 -0.1762889 0.05728209 -0.3189758 -0.151638 0.06865191 -0.3074553 -0.1807716 0.05841517 -0.3154594 -0.1528318 0.06537491 -0.2880529 -0.1809803 0.08061295 -0.3095269 -0.1847136 0.06018304 -0.3122497 -0.1879231 0.06256037 -0.315461 -0.1901667 0.06536853 -0.318992 -0.1913625 0.06864351 -0.2880365 -0.1859079 0.08057028 -0.2878302 -0.1872013 0.08111709 -0.2876303 -0.1892688 0.08105313 -0.2876642 -0.188364 0.08140319 -0.2879151 -0.187659 0.08049952 -0.2288239 -0.1537441 0.1827453 -0.2293039 -0.1544886 0.182907 -0.2221845 -0.1866862 0.1804986 -0.2294285 -0.1560428 0.1829683 -0.2233212 -0.1879681 0.1808832 -0.2259606 -0.1893451 0.1817758 -0.2286527 -0.1902635 0.1826891 -0.2249712 -0.1550953 0.1814411 -0.2223477 -0.1569528 0.1805535 -0.2294275 -0.1879362 0.1829754 -0.2293021 -0.1895208 0.1829066 -0.2290332 -0.1900631 0.1828208 -0.2456434 -0.1985 0.1228263 -0.246764 -0.1985 0.1221178 -0.2443891 -0.1985 0.1242153 -0.2475916 -0.1985 0.1323696 -0.2463718 -0.1985 0.1318499 -0.2494472 -0.1985 0.1326129 -0.2436931 -0.1985 0.1262045 -0.2436397 -0.1985 0.1275293 -0.2514796 -0.1985 0.1320558 -0.2439049 -0.1985 0.1288284 -0.2526003 -0.1985 0.1313471 -0.2444733 -0.1985 0.1300263 -0.2453117 -0.1985 0.1310534 -0.2535188 -0.1985 0.1303909 -0.2541817 -0.1985 0.1292425 -0.2545506 -0.1985 0.127969 -0.254604 -0.1985 0.1266441 -0.2543388 -0.1985 0.1253451 -0.2537704 -0.1985 0.1241472 -0.2529318 -0.1985 0.1231202 -0.2518718 -0.1985 0.1223236 -0.250652 -0.1985 0.1218039 -0.2493433 -0.1985 0.1215912 -0.2480217 -0.1985 0.1216979 -0.2436931 -0.1445 0.1262045 -0.2436397 -0.1445 0.1275293 -0.2442689 -0.1445 0.1244235 -0.2529318 -0.1445 0.1231202 -0.2518718 -0.1445 0.1223236 -0.2537704 -0.1445 0.1241472 -0.2456434 -0.1445 0.1228263 -0.2543388 -0.1445 0.1253451 -0.246764 -0.1445 0.1221178 -0.254604 -0.1445 0.1266441 -0.2480217 -0.1445 0.1216979 -0.2545506 -0.1445 0.127969 -0.2498908 -0.1445 0.1216047 -0.2541817 -0.1445 0.1292425 -0.2535188 -0.1445 0.1303909 -0.2526003 -0.1445 0.1313471 -0.2514796 -0.1445 0.1320558 -0.250222 -0.1445 0.1324756 -0.2489004 -0.1445 0.1325823 -0.2475916 -0.1445 0.1323696 -0.2463718 -0.1445 0.1318499 -0.2453117 -0.1445 0.1310534 -0.2444733 -0.1445 0.1300263 -0.2439049 -0.1445 0.1288284 -0.1274439 -0.2075743 0.1468716 -0.1280738 -0.2088268 0.1457728 -0.1287824 -0.2095183 0.1445384 -0.1271415 -0.2061128 0.1473978 -0.127084 -0.2043352 0.1474997 -0.1298968 -0.2095667 0.1425963 -0.1275014 -0.2022582 0.1467713 -0.1307026 -0.2088268 0.1411902 -0.1274439 -0.1415743 0.1468716 -0.1280738 -0.1428269 0.1457728 -0.1283513 -0.2008101 0.1452898 -0.1287824 -0.1435183 0.1445385 -0.1291093 -0.2003839 0.1439677 -0.1271415 -0.1401128 0.1473978 -0.1270837 -0.1383351 0.1474997 -0.1296671 -0.1436161 0.1429952 -0.1299949 -0.2004817 0.1424249 -0.1304258 -0.1431899 0.1416738 -0.1275014 -0.1362583 0.1467713 -0.1309701 -0.2015652 0.1407247 -0.1312758 -0.1417412 0.1401917 -0.1283513 -0.13481 0.1452898 -0.1315608 -0.2033442 0.1396949 -0.1291093 -0.1343839 0.1439677 -0.129995 -0.1344819 0.1424251 -0.1307026 -0.1351731 0.1411902 -0.1961122 -0.2075738 0.02716946 -0.1312759 -0.2077412 0.1401917 -0.1969304 -0.2090953 0.02574342 -0.19581 -0.2061128 0.02769535 -0.1317066 -0.2055656 0.1394412 -0.1985541 -0.211 0.02291184 -0.1980065 -0.2096784 0.02386766 -0.195752 -0.204335 0.0277974 -0.1990942 -0.2091898 0.0219711 -0.1991078 -0.2108746 0.02194654 -0.1996335 -0.2105048 0.02103012 -0.1961696 -0.2022587 0.02706927 -0.2001053 -0.2099092 0.02020764 -0.199944 -0.2077416 0.02048957 -0.2004989 -0.2091178 0.01952141 -0.2007955 -0.2081694 0.0190044 -0.2009796 -0.2071127 0.01868367 -0.2003031 -0.2061128 0.01986289 -0.2010419 -0.2060004 0.01857489 -0.2003633 -0.2044377 0.01975917 -0.2000015 -0.2024258 0.02038931 -0.196112 -0.1415739 0.02716946 -0.1967422 -0.2011731 0.02607035 -0.1969303 -0.1430954 0.02574342 -0.1316348 -0.1401128 0.1395653 -0.1975489 -0.200433 0.02466499 -0.19581 -0.1401128 0.02769535 -0.1980064 -0.1436785 0.02386754 -0.195752 -0.138335 0.0277974 -0.1316949 -0.1384371 0.1394613 -0.1986632 -0.2004817 0.02272242 -0.1990942 -0.1431899 0.0219711 -0.1961696 -0.1362588 0.02706927 -0.1313333 -0.136426 0.1400915 -0.199371 -0.2011731 0.02148783 -0.1997885 -0.1420835 0.02076005 -0.2002157 -0.1407542 0.02001613 -0.1967422 -0.1351731 0.02607035 -0.1975491 -0.1344333 0.02466505 -0.1986632 -0.1344817 0.02272242 -0.2003704 -0.1389999 0.01974564 -0.2002291 -0.1373442 0.01999258 -0.1996385 -0.1355652 0.02102226 -0.3298417 -0.1831863 0.0663225 -0.3305786 -0.1810484 0.06659913 -0.3260415 -0.1879888 0.06577062 -0.3273023 -0.183923 0.06409478 -0.3191803 -0.1740431 0.05656117 -0.3172374 -0.1715 0.05525094 -0.3211539 -0.1904826 0.06614834 -0.3237141 -0.1878629 0.063717 -0.3177918 -0.1893793 0.06319367 -0.3147262 -0.1872374 0.06049942 -0.3318894 -0.1817394 0.06812751 -0.3294792 -0.1870132 0.06877291 -0.3230788 -0.1906203 0.06784003 -0.3246165 -0.1904826 0.06919139 -0.3335791 -0.179746 0.0696125 -0.3340781 -0.1763457 0.06969058 -0.3267129 -0.1899304 0.07103377 -0.3322384 -0.1850666 0.07120841 -0.3210639 -0.1914446 0.0701496 -0.3285236 -0.189087 0.07262504 -0.3353017 -0.1761187 0.07111972 -0.3248547 -0.1907253 0.07348108 -0.3344772 -0.1824254 0.07317596 -0.3310429 -0.1872386 0.07483911 -0.334975 -0.1709929 0.07048428 -0.336164 -0.1791742 0.07465839 -0.3336402 -0.1841745 0.07712161 -0.3359606 -0.1715611 0.07170844 -0.3370983 -0.1760887 0.07547944 -0.335597 -0.1804028 0.07884138 -0.3375172 -0.1732568 0.07584762 -0.3366809 -0.1768234 0.07979393 -0.335651 -0.1685003 0.07143342 -0.3339197 -0.1663427 0.06955146 -0.3375589 -0.1703755 0.07588428 -0.3371669 -0.1735381 0.08022105 -0.3357595 -0.1736259 0.08306449 -0.3342972 -0.1643684 0.0702418 -0.3372224 -0.1675255 0.07558852 -0.3372152 -0.1701955 0.08026349 -0.3313524 -0.1625602 0.06728619 -0.3358099 -0.1701393 0.08310884 -0.3368249 -0.1668892 0.07992047 -0.336164 -0.1638258 0.07465839 -0.3318616 -0.161204 0.06809532 -0.3344772 -0.1605744 0.07317596 -0.335597 -0.1625972 0.07884138 -0.329896 -0.1598681 0.06637573 -0.3271687 -0.1608902 0.06358748 -0.3330617 -0.1587591 0.07193201 -0.3315979 -0.1573829 0.07064557 -0.3336402 -0.1588253 0.07712161 -0.3273631 -0.1590788 0.06414341 -0.3253648 -0.161471 0.06199318 -0.331998 -0.1567193 0.07567852 -0.3295973 -0.1560882 0.06888741 -0.3254557 -0.1591502 0.06247341 -0.3302999 -0.1551228 0.07418614 -0.3238522 -0.1619591 0.06066769 -0.319117 -0.1689406 0.05651319 -0.3262543 -0.155054 0.06593769 -0.3303677 -0.1560819 0.0783261 -0.327979 -0.1536208 0.07214647 -0.3232684 -0.1598679 0.06055116 -0.3198885 -0.1761348 0.0571829 -0.3285964 -0.1544166 0.07676935 -0.3222339 -0.1631488 0.05924648 -0.3175085 -0.1744751 0.05548924 -0.3150172 -0.1715 0.05442601 -0.3208841 -0.178173 0.05805939 -0.3183084 -0.1772831 0.05619221 -0.3237141 -0.1551371 0.063717 -0.3246165 -0.1525174 0.06919139 -0.3131845 -0.1754419 0.05446332 -0.3128252 -0.1715 0.0541476 -0.3106063 -0.1715 0.0543614 -0.3222324 -0.1798569 0.05924522 -0.3212739 -0.1612614 0.05879831 -0.3195872 -0.1797492 0.05731606 -0.323026 -0.1523789 0.0677936 -0.320884 -0.1648198 0.05806016 -0.3089385 -0.176073 0.05541312 -0.3085218 -0.1715 0.05504685 -0.3061315 -0.1715071 0.05651956 -0.3142443 -0.1791624 0.0553947 -0.320816 -0.1560881 0.0611701 -0.3238497 -0.1810443 0.0606659 -0.3212739 -0.1817384 0.05879831 -0.3211539 -0.1525174 0.06614834 -0.3195872 -0.1632508 0.05731606 -0.3254491 -0.1816472 0.06207114 -0.3159387 -0.1824298 0.05688375 -0.3210088 -0.1515544 0.0701012 -0.3181734 -0.1579344 0.05884772 -0.3198825 -0.1668565 0.05717933 -0.3101681 -0.1803891 0.05649363 -0.3232684 -0.1831321 0.06055116 -0.327185 -0.1820651 0.06360113 -0.3177918 -0.1536206 0.06319367 -0.3183084 -0.1657169 0.05619221 -0.3159387 -0.1605702 0.05688375 -0.3147262 -0.1557626 0.06049942 -0.3181734 -0.1850656 0.05884772 -0.3121337 -0.1841797 0.0582211 -0.3175085 -0.1685249 0.05548924 -0.3142443 -0.1638376 0.0553947 -0.3121337 -0.1588203 0.0582211 -0.3254557 -0.1838498 0.06247341 -0.3101681 -0.1626109 0.05649363 -0.3131845 -0.1675581 0.05446332 -0.3089385 -0.166927 0.05541312 -0.320816 -0.1869119 0.0611701 -0.2281232 -0.186109 0.1838814 -0.2280426 -0.1874985 0.1836902 -0.2283797 -0.1889311 0.1833496 -0.2290247 -0.1887145 0.1833119 -0.2291985 -0.1868456 0.1833226 -0.2288536 -0.1858822 0.1837295 -0.2286924 -0.187444 0.1837213 -0.2291979 -0.1571542 0.1833228 -0.2286776 -0.156544 0.183728 -0.2287579 -0.1549588 0.1833087 -0.2288811 -0.1581017 0.1837102 -0.2291142 -0.1552886 0.1832461 -0.2281274 -0.1579638 0.1838903 -0.2280436 -0.1565127 0.1836917 -0.2283467 -0.1548957 0.183268 -0.2534044 -0.1985 0.1282143 -0.245761 -0.1985 0.1299707 -0.2476168 -0.1985 0.1229218 -0.2526467 -0.1985 0.1297203 -0.2497251 -0.1985 0.1226995 -0.2463296 -0.1985 0.1236862 -0.2469324 -0.1985 0.1309034 -0.2452335 -0.1985 0.1249671 -0.2515796 -0.1985 0.1307707 -0.2516949 -0.1985 0.1234824 -0.248519 -0.1985 0.1314741 -0.2500139 -0.1985 0.1313953 -0.2446938 -0.1985 0.1270168 -0.253075 -0.1985 0.1250907 -0.2449521 -0.1985 0.1284916 -0.2535066 -0.1985 0.1267206 -0.2515796 -0.1445 0.1307707 -0.2497251 -0.1445 0.1226995 -0.2513113 -0.1445 0.1232702 -0.2449521 -0.1445 0.1284916 -0.2446938 -0.1445 0.1270168 -0.2530101 -0.1445 0.1292066 -0.245761 -0.1445 0.1299707 -0.2525365 -0.1445 0.1242828 -0.2452335 -0.1445 0.1249671 -0.2469324 -0.1445 0.1309034 -0.2535499 -0.1445 0.1271566 -0.2532915 -0.1445 0.1256819 -0.248519 -0.1445 0.1314741 -0.2463296 -0.1445 0.1236862 -0.2476168 -0.1445 0.1229218 -0.2500139 -0.1445 0.1313953 -0.1303563 -0.1385206 0.1466187 -0.1304256 -0.1398487 0.1464968 -0.1307415 -0.140727 0.1459462 -0.1325823 -0.1384496 0.1427385 -0.1313681 -0.1412809 0.1448549 -0.1320888 -0.137076 0.1435987 -0.1320153 -0.1409817 0.1437256 -0.1312984 -0.1367361 0.1449764 -0.1324755 -0.1400601 0.1429241 -0.1307048 -0.1373383 0.1460101 -0.1304255 -0.2058487 0.1464968 -0.1303489 -0.2047759 0.1466304 -0.1326097 -0.2049294 0.1426906 -0.1307414 -0.206727 0.1459462 -0.1313682 -0.2072808 0.1448549 -0.1323833 -0.2036734 0.143084 -0.131972 -0.2029725 0.1438011 -0.1320153 -0.2069817 0.1437256 -0.1314455 -0.2027361 0.1447187 -0.1324111 -0.2062456 0.1430355 -0.1309251 -0.2030181 0.145626 -0.1305292 -0.2037544 0.1463161 -0.1990173 -0.2047758 0.02692794 -0.1990939 -0.2058486 0.02679443 -0.1994098 -0.2067271 0.02624368 -0.2012601 -0.2047262 0.0230183 -0.2000365 -0.2072809 0.02515238 -0.2010517 -0.2036734 0.02338165 -0.20051 -0.2028346 0.02432709 -0.2006835 -0.2069819 0.02402347 -0.2011439 -0.2060601 0.02322179 -0.1998451 -0.2028136 0.0254848 -0.1992631 -0.203535 0.02650064 -0.1990232 -0.1393219 0.02691763 -0.1992254 -0.1403264 0.02656531 -0.201278 -0.1389294 0.02298814 -0.1996367 -0.1410274 0.0258482 -0.2010517 -0.1376734 0.02338165 -0.200163 -0.1412638 0.02493089 -0.20051 -0.1368345 0.02432709 -0.2006835 -0.1409819 0.02402347 -0.2010794 -0.1402457 0.02333325 -0.1998451 -0.1368137 0.0254848 -0.1993731 -0.1373382 0.02630758 -0.1990765 -0.1382433 0.02682471 -0.2514173 -0.1998 0.1308739 -0.2526467 -0.1998 0.1297203 -0.2503343 -0.1998 0.1228571 -0.2533515 -0.1998 0.1283992 -0.2518489 -0.1998 0.1235975 -0.2488493 -0.1998 0.1226667 -0.2534769 -0.1998 0.1262836 -0.2468261 -0.1998 0.1232996 -0.2528341 -0.1998 0.1247248 -0.2453293 -0.1998 0.1248003 -0.244701 -0.1998 0.1268246 -0.2449521 -0.1998 0.1284916 -0.2456389 -0.1998 0.129822 -0.2473088 -0.1998 0.1311272 -0.2493943 -0.1998 0.1315069 -0.2453293 -0.1442 0.1248003 -0.2468261 -0.1442 0.1232996 -0.252161 -0.1442 0.123905 -0.2508422 -0.1442 0.1230171 -0.253158 -0.1442 0.1252643 -0.2488493 -0.1442 0.1226667 -0.2535066 -0.1442 0.1267206 -0.2533515 -0.1442 0.1283992 -0.2526467 -0.1442 0.1297203 -0.2514173 -0.1442 0.1308739 -0.2493943 -0.1442 0.1315069 -0.2473088 -0.1442 0.1311272 -0.2456389 -0.1442 0.129822 -0.2449521 -0.1442 0.1284916 -0.244701 -0.1442 0.1268246 -0.132296 -0.1395888 0.1432358 -0.1313359 -0.1372386 0.1449095 -0.130698 -0.1398765 0.1460214 -0.1323375 -0.1387498 0.1431634 -0.1310797 -0.1405771 0.1453559 -0.1321153 -0.1377779 0.1435508 -0.1316041 -0.1407614 0.144442 -0.1317788 -0.1373637 0.1441375 -0.1305978 -0.1388256 0.146196 -0.1307885 -0.1378601 0.1458637 -0.1320653 -0.1402925 0.1436378 -0.1308745 -0.2037075 0.1457137 -0.1313359 -0.2032386 0.1449095 -0.132296 -0.2055888 0.1432358 -0.1307597 -0.206032 0.1459138 -0.1310797 -0.2065771 0.1453559 -0.1323375 -0.2047498 0.1431634 -0.1306024 -0.2052503 0.146188 -0.1316041 -0.2067614 0.144442 -0.1318602 -0.2034229 0.1439955 -0.1306439 -0.2044114 0.1461157 -0.1321803 -0.2039681 0.1434375 -0.1320653 -0.2062926 0.1436378 -0.2009509 -0.2056603 0.02355694 -0.1997481 -0.2034228 0.02565354 -0.2002724 -0.2032386 0.02473962 -0.2010104 -0.2048258 0.02345299 -0.1996123 -0.2064346 0.02589017 -0.1993122 -0.2055886 0.02641332 -0.2002181 -0.2067746 0.02483427 -0.2008199 -0.2038601 0.02378529 -0.1992707 -0.2047497 0.02648568 -0.199428 -0.2039679 0.0262115 -0.2007052 -0.2063433 0.0239852 -0.2010104 -0.1391742 0.02345299 -0.2008199 -0.1401398 0.02378529 -0.1998295 -0.1373637 0.02551162 -0.2002182 -0.1372253 0.02483421 -0.1993663 -0.1398764 0.02631908 -0.1997481 -0.1405771 0.02565354 -0.2009509 -0.1383396 0.02355694 -0.2002724 -0.1407613 0.02473962 -0.1992661 -0.1388257 0.02649366 -0.2007052 -0.1376566 0.0239852 -0.1994568 -0.1378601 0.02616137 -0.1382358 -0.1374228 0.1494612 -0.1378 -0.1395885 0.1502209 -0.1377585 -0.1387497 0.1502932 -0.1379158 -0.137968 0.150019 -0.1380307 -0.1402926 0.1498187 -0.138492 -0.1407614 0.1490146 -0.1391069 -0.140497 0.1479426 -0.1394407 -0.1396176 0.1473609 -0.1394982 -0.1388257 0.1472606 -0.1393077 -0.1378602 0.1475928 -0.1387602 -0.1372386 0.1485471 -0.1382358 -0.2034229 0.1494612 -0.1386451 -0.2032391 0.1487477 -0.1378 -0.2055885 0.1502209 -0.1377585 -0.2047497 0.1502932 -0.1379159 -0.203968 0.150019 -0.1380307 -0.2062926 0.1498187 -0.138492 -0.2067614 0.1490146 -0.1391069 -0.206497 0.1479426 -0.1394386 -0.2056604 0.1473646 -0.1394982 -0.2048258 0.1472606 -0.1393077 -0.2038602 0.1475928 -0.1389595 -0.2034086 0.1481997 -0.2076846 -0.2034229 0.02839827 -0.2071604 -0.2032386 0.02931231 -0.2064223 -0.2048257 0.03059881 -0.2064819 -0.2056603 0.03049492 -0.2068136 -0.206497 0.02991682 -0.206613 -0.2038601 0.03026658 -0.2074285 -0.2067614 0.02884483 -0.2078899 -0.2062925 0.02804064 -0.2081615 -0.2053728 0.02756708 -0.2080664 -0.2041234 0.02773284 -0.2068136 -0.1375029 0.02991676 -0.2064223 -0.1391742 0.03059881 -0.206613 -0.1401398 0.03026658 -0.2064819 -0.1383396 0.03049492 -0.2071604 -0.1407613 0.02931225 -0.2076846 -0.1405771 0.02839827 -0.2080664 -0.1398766 0.02773284 -0.2081615 -0.1386272 0.02756708 -0.2078899 -0.1377074 0.02804064 -0.2074285 -0.1372386 0.02884477 -0.1390186 -0.1404269 0.1480967 -0.1393408 -0.1381887 0.147535 -0.1379952 -0.1379448 0.1498807 -0.1378187 -0.1388385 0.1501883 -0.1388933 -0.1374403 0.1483152 -0.1386437 -0.1406301 0.1487502 -0.1379114 -0.1398112 0.1500267 -0.1384149 -0.1374257 0.149149 -0.1393499 -0.1397635 0.1475191 -0.1382647 -0.1404598 0.1494109 -0.1389406 -0.2065236 0.1482327 -0.1378187 -0.2048385 0.1501883 -0.1379951 -0.2039448 0.1498807 -0.1392956 -0.2040711 0.1476138 -0.1389873 -0.20354 0.1481512 -0.1394435 -0.205 0.1473559 -0.1384491 -0.2065913 0.1490893 -0.1384149 -0.2034257 0.149149 -0.1378739 -0.2056112 0.1500921 -0.1381013 -0.2062436 0.1496956 -0.1393036 -0.2058971 0.1475999 -0.206933 -0.2064598 0.02970844 -0.2067433 -0.2038034 0.03003925 -0.2080591 -0.2044549 0.02774554 -0.2064918 -0.2046548 0.03047764 -0.2073121 -0.2066301 0.02904778 -0.2070997 -0.2034125 0.02941787 -0.2080881 -0.2053931 0.02769494 -0.2075057 -0.2034257 0.02871036 -0.2065798 -0.2058114 0.03032428 -0.2077814 -0.2063279 0.02822977 -0.2078456 -0.2038034 0.02811783 -0.207687 -0.1404269 0.02839422 -0.208009 -0.1381886 0.02783274 -0.2064918 -0.1386548 0.03047764 -0.2076558 -0.1375401 0.02844864 -0.2073121 -0.1406301 0.02904778 -0.2072768 -0.1373698 0.02910923 -0.2081006 -0.1389999 0.0276733 -0.2069331 -0.1404598 0.02970844 -0.2080182 -0.1397636 0.02781677 -0.2065798 -0.1398114 0.03032428 -0.2068075 -0.1376721 0.02992731 -0.1488357 -0.1373698 0.1545969 -0.149305 -0.137672 0.1537789 -0.1495482 -0.1397702 0.1533549 -0.1496118 -0.1386067 0.1532441 -0.1491795 -0.1404598 0.1539977 -0.1488005 -0.1406301 0.1546584 -0.1484255 -0.1404269 0.155312 -0.1481406 -0.139897 0.1558088 -0.1479977 -0.1389492 0.1560578 -0.1481606 -0.1380446 0.1557738 -0.1484568 -0.1375401 0.1552575 -0.1485509 -0.2034403 0.1550934 -0.1490293 -0.2034257 0.1542595 -0.1496258 -0.205197 0.1532198 -0.1493692 -0.2038033 0.153667 -0.1494757 -0.2059551 0.1534813 -0.1495749 -0.204423 0.1533083 -0.1491795 -0.2064598 0.1539976 -0.1488005 -0.2066301 0.1546584 -0.1484256 -0.2064269 0.155312 -0.1481406 -0.205897 0.1558088 -0.1479977 -0.2049492 0.1560578 -0.1481606 -0.2040446 0.1557738 -0.217388 -0.2033692 0.03509694 -0.2182941 -0.205197 0.03351742 -0.2178478 -0.2035401 0.03429549 -0.2181441 -0.2059552 0.03377902 -0.2182012 -0.2041887 0.03367948 -0.2178478 -0.2064598 0.03429543 -0.2174689 -0.2066301 0.03495597 -0.217094 -0.2064269 0.0356096 -0.2168089 -0.205897 0.0361064 -0.2166791 -0.2051613 0.03633266 -0.2167343 -0.2043887 0.03623646 -0.2169617 -0.2037565 0.03584015 -0.2175041 -0.1373698 0.03489458 -0.217879 -0.137573 0.03424108 -0.2182896 -0.1392316 0.03352528 -0.2181441 -0.1399552 0.03377902 -0.2182247 -0.1382786 0.03363853 -0.2178478 -0.1404598 0.03429543 -0.2174689 -0.1406301 0.03495597 -0.217094 -0.1404269 0.0356096 -0.2168089 -0.139897 0.0361064 -0.2166791 -0.1391613 0.03633266 -0.2167343 -0.1383888 0.03623646 -0.2170413 -0.1376143 0.03570151 -0.2373206 -0.1487579 0.1008335 -0.2392408 -0.1494885 0.1017063 -0.2374015 -0.1495 0.1006925 -0.2353308 -0.1494849 0.1043021 -0.2371485 -0.1494388 0.1053538 -0.2355426 -0.1483678 0.103933 -0.2374039 -0.1482658 0.1049084 -0.2360025 -0.1476387 0.1031312 -0.2377184 -0.1477617 0.1043604 -0.2381759 -0.1475085 0.1035628 -0.2366003 -0.1475717 0.1020891 -0.2386846 -0.1477622 0.102676 -0.2370308 -0.1479927 0.1013387 -0.2390412 -0.1483957 0.1020545 -0.2298564 -0.1487575 0.1138449 -0.2317771 -0.1494884 0.1147173 -0.2299374 -0.1495 0.1137037 -0.227867 -0.1494849 0.1173131 -0.2296849 -0.1494386 0.118365 -0.2280786 -0.1483678 0.1169441 -0.2299399 -0.1482661 0.1179201 -0.2285386 -0.1476386 0.1161423 -0.2302547 -0.1477615 0.1173711 -0.230712 -0.1475085 0.1165739 -0.2291363 -0.1475717 0.1151004 -0.2312207 -0.1477623 0.115687 -0.2295668 -0.1479925 0.11435 -0.2315773 -0.1483961 0.1150655 -0.2298613 -0.1935304 0.1138365 -0.2316576 -0.1935 0.1149256 -0.2317729 -0.1942242 0.1147244 -0.2299222 -0.1949396 0.1137306 -0.2295969 -0.1959562 0.1142975 -0.2291668 -0.1964151 0.1150472 -0.2278905 -0.1947376 0.1172719 -0.2279594 -0.193516 0.117152 -0.2286819 -0.1964266 0.1158924 -0.2281534 -0.1958476 0.1168138 -0.2297936 -0.1935071 0.1181752 -0.2297061 -0.1946589 0.1183274 -0.2298688 -0.1955413 0.118044 -0.2301664 -0.1961358 0.117525 -0.2305759 -0.196456 0.1168115 -0.2310505 -0.1963829 0.1159839 -0.2316849 -0.1951989 0.1148776 -0.2314569 -0.1958866 0.1152753 -0.2373252 -0.1935304 0.1008254 -0.2391215 -0.1935 0.1019144 -0.2392369 -0.1942237 0.1017133 -0.2373862 -0.1949401 0.1007195 -0.2370609 -0.1959562 0.1012864 -0.2366307 -0.1964151 0.1020359 -0.2353544 -0.1947371 0.104261 -0.2354233 -0.193516 0.1041408 -0.2361458 -0.1964266 0.1028813 -0.2356171 -0.1958472 0.1038031 -0.2372572 -0.1935071 0.1051639 -0.2391489 -0.1951999 0.1018669 -0.2376306 -0.196136 0.1045134 -0.2389209 -0.1958865 0.1022641 -0.2371701 -0.1946589 0.1053165 -0.2373327 -0.1955416 0.1050326 -0.2380396 -0.196456 0.1038001 -0.2385144 -0.1963829 0.1029726 -0.2223926 -0.1487578 0.1268559 -0.2243129 -0.1494884 0.1277285 -0.2224736 -0.1495 0.1267148 -0.2204029 -0.1494849 0.1303243 -0.2222205 -0.1494388 0.1313761 -0.2206147 -0.1483677 0.1299552 -0.222476 -0.1482658 0.1309307 -0.2210746 -0.1476387 0.1291536 -0.2227906 -0.1477616 0.1303825 -0.223248 -0.1475085 0.129585 -0.2216724 -0.1475717 0.1281115 -0.2237567 -0.1477622 0.1286982 -0.2221028 -0.1479926 0.1273611 -0.2241133 -0.1483958 0.1280769 -0.2223973 -0.1935304 0.1268477 -0.2241936 -0.1935 0.1279367 -0.224309 -0.1942235 0.1277357 -0.2224583 -0.1949393 0.1267417 -0.2221329 -0.1959562 0.1273087 -0.2204958 -0.193516 0.1301624 -0.2217029 -0.1964151 0.1280582 -0.2204265 -0.1947366 0.1302832 -0.2212178 -0.1964266 0.1289037 -0.2206891 -0.195847 0.1298254 -0.2223294 -0.1935068 0.1311849 -0.222242 -0.1946571 0.1313387 -0.2227027 -0.1961359 0.1305358 -0.2231118 -0.196456 0.1298224 -0.2224046 -0.1955413 0.131055 -0.2235864 -0.1963829 0.128995 -0.2242215 -0.1951977 0.1278885 -0.2239931 -0.1958864 0.1282863 -0.2149286 -0.1487578 0.1398671 -0.2168478 -0.1494773 0.1407419 -0.2150096 -0.1495 0.1397259 -0.2129408 -0.1494708 0.1433324 -0.2147531 -0.1494672 0.144394 -0.2131506 -0.1483681 0.1429665 -0.2150121 -0.1482659 0.1439419 -0.2136107 -0.1476387 0.1421646 -0.2153266 -0.1477616 0.1433936 -0.2157841 -0.1475085 0.1425961 -0.2142084 -0.1475717 0.1411226 -0.2162928 -0.1477622 0.1417094 -0.2146389 -0.1479926 0.1403721 -0.2166492 -0.1483958 0.141088 -0.2149334 -0.1935304 0.1398588 -0.2167297 -0.1935 0.1409478 -0.2168449 -0.1942238 0.1407467 -0.2149942 -0.1949397 0.1397528 -0.214669 -0.1959561 0.1403197 -0.214239 -0.1964151 0.1410694 -0.213754 -0.1964266 0.1419148 -0.2129626 -0.194738 0.1432942 -0.2130314 -0.193516 0.1431743 -0.2132254 -0.1958475 0.1428362 -0.2148654 -0.1935071 0.1441975 -0.2147783 -0.19466 0.1443498 -0.2149412 -0.1955421 0.1440659 -0.2152387 -0.1961359 0.1435468 -0.2156481 -0.196456 0.1428335 -0.2161226 -0.1963829 0.142006 -0.2167571 -0.1951983 0.1408997 -0.2165291 -0.1958864 0.1412975 -0.1990018 -0.206 0.0370028 -0.204973 -0.194 0.02659392 -0.204973 -0.15 0.02659392 -0.1990018 -0.138 0.0370028 -0.1412806 -0.206 0.1376222 -0.1412806 -0.138 0.1376222 -0.1353093 -0.194 0.1480311 -0.1353093 -0.15 0.1480311 -0.2007226 -0.194 0.02415567 -0.2007226 -0.15 0.02415567 -0.1947515 -0.138 0.03456461 -0.1370303 -0.138 0.135184 -0.1310591 -0.15 0.1455929 -0.1310591 -0.194 0.1455929 -0.1370303 -0.206 0.135184 -0.1947515 -0.206 0.03456461 -0.2447746 -0.1935042 0.08783966 -0.2465855 -0.1935 0.0889033 -0.2467008 -0.1942241 0.08870214 -0.244868 -0.1942873 0.08767688 -0.244809 -0.1951324 0.08777976 -0.2445248 -0.1959561 0.08827519 -0.2440947 -0.1964151 0.0890249 -0.2428184 -0.1947377 0.0912497 -0.2428856 -0.193531 0.0911327 -0.2436098 -0.1964266 0.08987027 -0.2430813 -0.1958476 0.09079158 -0.2447215 -0.1935057 0.09215235 -0.246613 -0.195198 0.0888552 -0.2463849 -0.1958866 0.089253 -0.2450945 -0.1961359 0.09150242 -0.244634 -0.1946594 0.09230524 -0.2447968 -0.1955417 0.09202146 -0.2455037 -0.196456 0.09078907 -0.2459784 -0.1963829 0.08996152 -0.2447845 -0.1487578 0.08782255 -0.2467036 -0.1494773 0.08869743 -0.2448654 -0.1495 0.08768141 -0.2427965 -0.1494708 0.09128791 -0.2446086 -0.1494672 0.09234941 -0.2430064 -0.148368 0.09092193 -0.2448678 -0.1482661 0.09189766 -0.2434665 -0.1476386 0.09012013 -0.2451825 -0.1477615 0.091349 -0.2456399 -0.1475085 0.09055161 -0.2440642 -0.1475717 0.08907812 -0.2461486 -0.1477623 0.08966481 -0.2444947 -0.1479926 0.0883277 -0.2465051 -0.1483959 0.08904337 -0.2095192 0.03106999 0.1102582 -0.2314976 0.03097623 0.1221905 -0.2102091 0.03104823 0.1090632 -0.2320623 0.03118991 0.1212125 -0.2113027 0.03500401 0.1071692 -0.2330304 0.03399497 0.1195357 -0.23293 0.0351268 0.1197095 -0.211375 0.03363168 0.1070439 -0.2108561 0.0316919 0.1079427 -0.2325559 0.03177887 0.1203576 -0.2109051 0.03621101 0.1078576 -0.2326532 0.03598433 0.1201891 -0.2112079 0.03260082 0.1073333 -0.2329533 0.0329858 0.1196692 -0.2322304 0.03666239 0.1209213 -0.2104117 0.03680002 0.1087125 -0.2315632 0.0370137 0.1220769 -0.2098469 0.0370137 0.1096905 -0.2309985 0.03680002 0.1230551 -0.2091493 0.03663754 0.1108989 -0.2305315 0.03624981 0.1238638 -0.2086189 0.03565585 0.1118175 -0.2301307 0.0351268 0.124558 -0.2084233 0.03471291 0.1121563 -0.2300304 0.03399497 0.1247318 -0.2083852 0.03356599 0.1122221 -0.2301074 0.03298574 0.1245983 -0.2086562 0.03222608 0.1117529 -0.2305049 0.03177893 0.1239099 -0.2090276 0.03152602 0.1111096 -0.2309985 0.03118991 0.1230551 -0.2196026 -0.04277163 0.1107934 -0.2334589 -0.04277163 0.1187934 -0.2372041 -0.0409255 0.1123067 -0.2157454 -0.04277163 0.1174741 -0.233674 -0.01100498 0.08642089 -0.2475304 -0.01100498 0.0944209 -0.2470654 -0.00334686 0.09522622 -0.2233477 -0.0409255 0.1043066 -0.2406194 -0.03734046 0.1063911 -0.233209 -0.00334686 0.08722621 -0.2456977 0.003866136 0.09759527 -0.226763 -0.03734046 0.09839105 -0.2435065 -0.03222489 0.1013904 -0.2318413 0.003866136 0.08959525 -0.2435065 0.01021492 0.1013904 -0.2296501 -0.03222489 0.0933904 -0.2456977 -0.0258761 0.09759527 -0.2296501 0.01021492 0.0933904 -0.2406194 0.01533043 0.1063911 -0.2318413 -0.0258761 0.08959525 -0.2470654 -0.01866304 0.09522622 -0.233209 -0.01866304 0.08722621 -0.226763 0.01533043 0.09839105 -0.2372041 0.01891547 0.1123067 -0.2233477 0.01891547 0.1043066 -0.2334589 0.02076166 0.1187934 -0.2196026 0.02076166 0.1107934 -0.2296018 0.02076166 0.1254742 -0.2157454 0.02076166 0.1174741 -0.2258567 0.01891547 0.1319609 -0.2120003 0.01891547 0.1239609 -0.2224413 0.01533043 0.1378764 -0.2085849 0.01533043 0.1298764 -0.2195542 0.01021492 0.1428771 -0.2056978 0.01021492 0.1348771 -0.2173631 0.003866136 0.1466722 -0.2035067 0.003866136 0.1386722 -0.2159953 -0.00334686 0.1490412 -0.2021389 -0.00334686 0.1410413 -0.2155303 -0.01100498 0.1498466 -0.201674 -0.01100498 0.1418465 -0.2159953 -0.01866304 0.1490412 -0.2021389 -0.01866304 0.1410413 -0.2173631 -0.0258761 0.1466722 -0.2035067 -0.0258761 0.1386722 -0.2195542 -0.03222489 0.1428771 -0.2056978 -0.03222489 0.1348771 -0.2224413 -0.03734046 0.1378764 -0.2085849 -0.03734046 0.1298764 -0.2258567 -0.0409255 0.1319609 -0.2120003 -0.0409255 0.1239609 -0.2296018 -0.04277163 0.1254742 -0.1985764 1.2554e-4 0.127596 -0.2002164 0.004877328 0.1247555 -0.2000071 0.006121337 0.1262561 -0.1982387 9.97328e-4 0.1293191 -0.2014952 0.005244433 0.1221553 -0.1980676 -0.006322801 0.1280898 -0.1971347 -0.004824221 0.1312311 -0.1983253 0.001950442 0.1314662 -0.1971338 -0.004333376 0.1335301 -0.1967288 -0.01100498 0.1342316 -0.1976777 -0.003920257 0.1357794 -0.1972476 -0.01100498 0.1365244 -0.1976777 -0.01808971 0.1357794 -0.1982873 -0.01100498 0.1386327 -0.1987364 -0.01840221 0.1378549 -0.2000575 -0.02536958 0.1355665 -0.2002513 -0.01859694 0.1396417 -0.2016073 -0.02574771 0.1372931 -0.2037795 -0.03204166 0.1335307 -0.1975527 -0.005273163 0.1293691 -0.1967595 -0.01100498 0.1318811 -0.1971338 -0.01767659 0.1335301 -0.198943 -0.02476269 0.1335877 -0.202174 -0.03150212 0.1319006 -0.2066417 -0.03711307 0.1285732 -0.1972047 -0.01100498 0.1299719 -0.1971347 -0.01718574 0.1312311 -0.1983253 -0.02396047 0.1314662 -0.2009701 -0.03063607 0.1300767 -0.2049628 -0.03644347 0.1270703 -0.2100276 -0.04066717 0.1227087 -0.1975527 -0.0167368 0.1293691 -0.1987524 -0.01930409 0.1269055 -0.1982387 -0.02300733 0.1293191 -0.2002342 -0.02949142 0.1281599 -0.2036411 -0.03536862 0.1254505 -0.2082619 -0.03990638 0.1213562 -0.2137403 -0.04249739 0.1162781 -0.1985764 -0.02213549 0.127596 -0.2000071 -0.02813136 0.1262561 -0.2027495 -0.033948 0.1238034 -0.2068006 -0.03868526 0.1199778 -0.2118794 -0.04168969 0.1150904 -0.2175642 -0.04249739 0.109655 -0.2002164 -0.02688735 0.1247555 -0.2018553 -0.02789056 0.1215313 -0.2023373 -0.03226006 0.12222 -0.2057248 -0.03707122 0.1186498 -0.2102653 -0.04039317 0.1139768 -0.2156051 -0.04168969 0.1086372 -0.2212769 -0.04066717 0.1032243 -0.2023773 -0.03071618 0.1210127 -0.2050938 -0.0351535 0.1174457 -0.2089875 -0.03867954 0.1129988 -0.2138338 -0.04039317 0.1077962 -0.2192227 -0.03990638 0.1023714 -0.2246628 -0.03711307 0.09735977 -0.2049336 -0.03339946 0.1165851 -0.2080074 -0.03330105 0.1108739 -0.2081164 -0.0366435 0.1122104 -0.231514 -0.01100498 0.08549296 -0.2123478 -0.03867954 0.1071786 -0.2172985 -0.03868526 0.1017951 -0.2225218 -0.03644347 0.09665733 -0.2275249 -0.03204166 0.09240227 -0.2077366 -0.03478121 0.11173 -0.2112295 -0.0366435 0.1068184 -0.2156105 -0.03707122 0.1015275 -0.2310532 -0.003413021 0.08629131 -0.2204581 -0.03536862 0.09632253 -0.2287482 -0.00360769 0.08587276 -0.2291973 -0.01100498 0.08509486 -0.2253106 -0.03150212 0.09182697 -0.2296973 0.003737688 0.08863991 -0.2296973 -0.02574771 0.08863991 -0.2264215 -0.003920257 0.08599364 -0.2268516 -0.01100498 0.08524864 -0.2106236 -0.03478121 0.1067297 -0.227427 0.003359615 0.08816111 -0.2142521 -0.0351535 0.101583 -0.2185859 -0.033948 0.09637391 -0.2275249 0.0100317 0.09240227 -0.223129 -0.03063607 0.09169626 -0.2242016 -0.004333376 0.08664727 -0.2246066 -0.01100498 0.08594572 -0.2251561 0.002752661 0.08818531 -0.227427 -0.02536958 0.08816111 -0.2310532 -0.01859694 0.08629131 -0.2253106 0.009492158 0.09182697 -0.2134267 -0.03339946 0.1018746 -0.2143685 -0.03037446 0.09985709 -0.2246628 0.01510304 0.09735977 -0.2170086 -0.03226006 0.09680861 -0.2222111 -0.004824221 0.08779758 -0.2225863 -0.01100498 0.08714765 -0.2211011 -0.02949142 0.09201741 -0.22301 0.001950442 0.08871114 -0.2251561 -0.02476269 0.08818531 -0.223129 0.008626103 0.09169626 -0.2287482 -0.01840221 0.08587276 -0.215983 -0.03071618 0.09744697 -0.2225218 0.01443344 0.09665733 -0.2212769 0.01865714 0.1032243 -0.2193388 -0.02813136 0.0927726 -0.2208076 -0.005273163 0.08909046 -0.2192738 -0.002705812 0.09136134 -0.2209396 -0.01100492 0.08873432 -0.22301 -0.02396047 0.08871114 -0.2211072 9.97328e-4 0.08970963 -0.2264215 -0.01808971 0.08599364 -0.2211011 0.007481396 0.09201741 -0.2181439 -0.02688735 0.0937041 -0.2204581 0.01335865 0.09632253 -0.2188845 -0.02136868 0.09203481 -0.2211072 -0.02300733 0.08970963 -0.2192227 0.01789641 0.1023714 -0.2242016 -0.01767659 0.08664727 -0.2175642 0.02048736 0.109655 -0.2197839 -0.02213549 0.09086358 -0.2197839 1.2554e-4 0.09086358 -0.2222111 -0.01718574 0.08779758 -0.2208076 -0.0167368 0.08909046 -0.2193388 0.006121337 0.0927726 -0.2185859 0.01193797 0.09637391 -0.2172985 0.01667523 0.1017951 -0.2156051 0.01967966 0.1086372 -0.2137403 0.02048736 0.1162781 -0.2181439 0.004877328 0.0937041 -0.2161725 0.005882084 0.09673374 -0.2170086 0.01025003 0.09680861 -0.2156105 0.01506119 0.1015275 -0.2138338 0.0183832 0.1077962 -0.2118794 0.01967966 0.1150904 -0.2100276 0.01865714 0.1227087 -0.215983 0.008706152 0.09744697 -0.2142521 0.01314347 0.101583 -0.2123478 0.01666957 0.1071786 -0.2102653 0.0183832 0.1139768 -0.2082619 0.01789641 0.1213562 -0.2066417 0.01510304 0.1285732 -0.2134267 0.01138943 0.1018746 -0.211427 0.01059812 0.1049523 -0.2112295 0.01463347 0.1068184 -0.2089875 0.01666957 0.1129988 -0.2068006 0.01667523 0.1199778 -0.2049628 0.01443344 0.1270703 -0.2037795 0.0100317 0.1335307 -0.2106236 0.01277124 0.1067297 -0.2081164 0.01463347 0.1122104 -0.2057248 0.01506119 0.1186498 -0.2036411 0.01335865 0.1254505 -0.202174 0.009492158 0.1319006 -0.2016073 0.003737688 0.1372931 -0.2077366 0.01277124 0.11173 -0.2061323 0.0103693 0.1141234 -0.2050938 0.01314347 0.1174457 -0.2027495 0.01193797 0.1238034 -0.2009701 0.008626103 0.1300767 -0.2000575 0.003359615 0.1355665 -0.2002513 -0.003413021 0.1396417 -0.2049336 0.01138943 0.1165851 -0.2023373 0.01025003 0.12222 -0.2002342 0.007481396 0.1281599 -0.198943 0.002752661 0.1335877 -0.1987364 -0.00360769 0.1378549 -0.1997904 -0.01100498 0.1404401 -0.2023773 0.008706152 0.1210127 -0.2974447 0.07099497 0.0872631 -0.274928 0.07099497 0.07426309 -0.274928 0.06899499 0.07426309 -0.2974447 0.06899499 0.0872631 -0.261928 0.06899499 0.09677976 -0.261928 0.07099497 0.09677976 -0.2844447 0.06899499 0.1097798 -0.2887209 0.07099497 0.09630835 -0.2894843 0.07099497 0.09402167 -0.2896783 0.07099497 0.09161877 -0.2844447 0.07099497 0.1097798 -0.2874324 0.07099497 0.09834587 -0.2892916 0.07099497 0.08923929 -0.2856938 0.07099497 0.1000159 -0.2883466 0.07099497 0.08702147 -0.283606 0.07099497 0.1012213 -0.2868984 0.07099497 0.08509421 -0.2812905 0.07099497 0.101892 -0.285031 0.07099497 0.08356952 -0.2788817 0.07099497 0.101989 -0.2765197 0.07099497 0.1015068 -0.2743417 0.07099497 0.1004734 -0.273679 0.07099497 0.08402699 -0.2719403 0.07099497 0.08569699 -0.2757667 0.07099497 0.08282166 -0.2780823 0.07099497 0.08215093 -0.2804911 0.07099497 0.08205389 -0.2828531 0.07099497 0.0825361 -0.2706519 0.07099497 0.08773452 -0.2700812 0.07099497 0.09480363 -0.2710261 0.07099497 0.09702146 -0.2696945 0.07099497 0.09242409 -0.2698885 0.07099497 0.09002119 -0.2724744 0.07099497 0.09894871 -0.2874324 0.07899498 0.09834587 -0.2887209 0.07899498 0.09630835 -0.2856938 0.07899498 0.1000159 -0.283606 0.07899498 0.1012213 -0.2700812 0.07899498 0.09480363 -0.2710261 0.07899498 0.09702146 -0.2812905 0.07899498 0.101892 -0.2696945 0.07899498 0.09242409 -0.2788817 0.07899498 0.101989 -0.2698885 0.07899498 0.09002119 -0.2765197 0.07899498 0.1015068 -0.2706519 0.07899498 0.08773452 -0.2719403 0.07899498 0.08569699 -0.2743417 0.07899498 0.1004734 -0.2724744 0.07899498 0.09894871 -0.273679 0.07899498 0.08402699 -0.2757667 0.07899498 0.08282166 -0.2780823 0.07899498 0.08215093 -0.2804911 0.07899498 0.08205389 -0.2828531 0.07899498 0.0825361 -0.285031 0.07899498 0.08356952 -0.2868984 0.07899498 0.08509421 -0.2883466 0.07899498 0.08702147 -0.2892916 0.07899498 0.08923929 -0.2896783 0.07899498 0.09161877 -0.2894843 0.07899498 0.09402167 -0.2727582 0.07899498 0.09602141 -0.2739168 0.07899498 0.09756326 -0.2784031 0.07899498 0.08412504 -0.2765507 0.07899498 0.0846616 -0.2720022 0.07899498 0.09424716 -0.2875247 0.07899498 0.09362167 -0.286914 0.07899498 0.09545099 -0.2876799 0.07899498 0.0916993 -0.2748804 0.07899498 0.08562588 -0.2858832 0.07899498 0.097081 -0.2873705 0.07899498 0.0897957 -0.2734895 0.07899498 0.08696186 -0.2844923 0.07899498 0.09841698 -0.2716929 0.07899498 0.09234356 -0.2718481 0.07899498 0.09042125 -0.2724588 0.07899498 0.08859193 -0.2866146 0.07899498 0.08802145 -0.2828221 0.07899498 0.09938126 -0.285456 0.07899498 0.08647966 -0.2809697 0.07899498 0.09991782 -0.2839621 0.07899498 0.08525991 -0.2790427 0.07899498 0.09999549 -0.2822197 0.07899498 0.08443313 -0.277153 0.07899498 0.09960973 -0.2803301 0.07899498 0.08404737 -0.2754106 0.07899498 0.09878295 -0.2858832 0.08999496 0.097081 -0.286914 0.08999496 0.09545099 -0.2844923 0.08999496 0.09841698 -0.2720022 0.08999496 0.09424716 -0.2727582 0.08999496 0.09602141 -0.2828221 0.08999496 0.09938126 -0.2809697 0.08999496 0.09991782 -0.2716929 0.08999496 0.09234356 -0.2718481 0.08999496 0.09042125 -0.2790427 0.08999496 0.09999549 -0.2724588 0.08999496 0.08859193 -0.277153 0.08999496 0.09960973 -0.2734895 0.08999496 0.08696186 -0.2754106 0.08999496 0.09878295 -0.2739168 0.08999496 0.09756326 -0.2748804 0.08999496 0.08562588 -0.2765507 0.08999496 0.0846616 -0.2784031 0.08999496 0.08412504 -0.2803301 0.08999496 0.08404737 -0.2822197 0.08999496 0.08443313 -0.2839621 0.08999496 0.08525991 -0.285456 0.08999496 0.08647966 -0.2866146 0.08999496 0.08802145 -0.2873705 0.08999496 0.0897957 -0.2876799 0.08999496 0.0916993 -0.2875247 0.08999496 0.09362167 -0.2832666 0.07056349 0.1605204 -0.26555 0.06899499 0.1729435 -0.2655315 0.07043242 0.1729171 -0.2832229 0.06899493 0.1605731 -0.2843036 0.06899505 0.1591473 -0.2844347 0.07056307 0.1587971 -0.2848182 0.06899499 0.1568978 -0.2847578 0.07055753 0.1572323 -0.2847021 0.07054883 0.1561141 -0.2843028 0.06899499 0.1547169 -0.2842584 0.07056045 0.1547101 -0.2651022 0.07215219 0.1720013 -0.2825614 0.07228064 0.1597586 -0.2500727 0.06899499 0.1464388 -0.2477932 0.06899499 0.1439951 -0.2475315 0.06899493 0.1447345 -0.2461809 0.06899493 0.1422099 -0.2428125 0.06899487 0.1401271 -0.2454231 0.06899499 0.142414 -0.2709246 0.06899493 0.1341888 -0.2695077 0.06899166 0.1334975 -0.2494832 0.06899499 0.1472185 -0.2447396 0.06899493 0.1430771 -0.2663227 0.06899487 0.12902 -0.2640187 0.06899493 0.1315845 -0.2647919 0.06899511 0.127839 -0.263325 0.06899499 0.1309314 -0.2469407 0.06899499 0.1452516 -0.2625426 0.06899499 0.1273244 -0.2625646 0.06899493 0.1307387 -0.264177 0.06899499 0.1325239 -0.2492458 0.06899499 0.1483585 -0.2460096 0.06899493 0.1454519 -0.2806616 0.06899499 0.148783 -0.2416759 0.06899517 0.1416114 -0.2605112 0.06899499 0.1277859 -0.2807726 0.06899499 0.1496232 -0.2639153 0.06899493 0.1332635 -0.261807 0.06899499 0.1309428 -0.2611235 0.06899493 0.1316059 -0.2445954 0.06899499 0.1440185 -0.2411613 0.06899499 0.1438606 -0.2759448 0.06899499 0.1542831 -0.2622113 0.06899499 0.1639004 -0.2648447 0.06899493 0.1676316 -0.2785379 0.06899493 0.1579837 -0.2667067 0.06899499 0.1374086 -0.2659245 0.06899499 0.1368327 -0.2641513 0.06899499 0.1669788 -0.2633907 0.06899493 0.1667858 -0.2609792 0.06899499 0.1325476 -0.2650029 0.06899499 0.1685711 -0.2647774 0.06899499 0.1365981 -0.2416521 0.06899499 0.1459734 -0.2633246 0.06899499 0.1337804 -0.2611531 0.06899499 0.1641632 -0.2626328 0.06899499 0.1669899 -0.2638126 0.06899499 0.1368446 -0.2623933 0.06899493 0.1339807 -0.2613283 0.06899493 0.1334076 -0.2449444 0.06899493 0.1448787 -0.2764927 0.06899499 0.1514118 -0.2495045 0.06899499 0.1493902 -0.2812284 0.06899493 0.1561606 -0.2619493 0.06899493 0.1676532 -0.2805351 0.06899499 0.1555076 -0.2600367 0.06899499 0.1639158 -0.2797745 0.06899493 0.1553147 -0.2767354 0.06899499 0.1524192 -0.2813867 0.06899499 0.1570999 -0.2647413 0.06899493 0.1693103 -0.2641505 0.06899499 0.1698276 -0.2811251 0.06899493 0.1578392 -0.2790166 0.06899499 0.1555188 -0.2764939 0.06899499 0.1535376 -0.2632193 0.06899493 0.1700277 -0.2634372 0.06899499 0.1734343 -0.2611874 0.06899511 0.1729195 -0.259301 0.06899499 0.1633756 -0.259674 0.06899493 0.171755 -0.2783332 0.06899493 0.156182 -0.2621543 0.06899493 0.1694549 -0.2618051 0.06899499 0.1685946 -0.2805342 0.06899499 0.1583566 -0.2796032 0.06899493 0.1585566 -0.2781889 0.06899499 0.1571233 -0.247635 0.06899493 0.1430557 -0.2469413 0.06899499 0.1424026 -0.2597748 0.07039237 0.1718693 -0.2615085 0.0703814 0.1730599 -0.263074 0.07040464 0.1733832 -0.2641921 0.07041811 0.1733273 -0.2817425 0.07047587 0.1510237 -0.2813292 0.06959468 0.1504241 -0.2834206 0.07228285 0.1585448 -0.2837667 0.07227456 0.1567889 -0.2833671 0.07225793 0.1551702 -0.2605142 0.07208967 0.1711959 -0.2617277 0.07211101 0.172055 -0.2634835 0.07213521 0.1724011 -0.2631815 0.07211393 0.1699827 -0.2624578 0.07210302 0.1697109 -0.2639483 0.07212269 0.1698809 -0.2619445 0.07209265 0.1691455 -0.2645853 0.0721274 0.1694341 -0.2617543 0.07208496 0.1683939 -0.2649808 0.07212603 0.1685616 -0.2589492 0.072043 0.1673792 -0.2576746 0.07198631 0.1673094 -0.2602165 0.07205593 0.1669961 -0.2619317 0.07208174 0.167641 -0.2625951 0.07208502 0.1669473 -0.2635383 0.07209545 0.166777 -0.2716206 0.0721665 0.1642639 -0.2704156 0.07215869 0.1638278 -0.2647865 0.07211691 0.1676211 -0.2728834 0.07217377 0.1635554 -0.2642675 0.07210642 0.1670479 -0.2699632 0.07214212 0.1628324 -0.2701795 0.07214087 0.1617481 -0.2731494 0.07217818 0.162471 -0.2795639 0.07223463 0.1585108 -0.2788404 0.07222378 0.1582392 -0.2803305 0.07224339 0.1584089 -0.2725242 0.07216137 0.1613156 -0.2783267 0.07221335 0.1576734 -0.2809675 0.0722481 0.1579625 -0.2781366 0.07220566 0.1569221 -0.2813631 0.07224673 0.1570895 -0.2711797 0.07214921 0.1610563 -0.2783141 0.07220244 0.1561688 -0.2811688 0.07223761 0.156149 -0.2806494 0.07222712 0.1555756 -0.2813544 0.07221221 0.152235 -0.2799205 0.07221615 0.1553052 -0.2789776 0.07220572 0.1554753 -0.2857949 0.07303053 0.1444683 -0.2859179 0.07290226 0.1454298 -0.2863758 0.07330161 0.1465401 -0.2865998 0.07437652 0.147849 -0.2816764 0.0712437 0.151706 -0.287931 0.07625871 0.147452 -0.287421 0.07699167 0.1479194 -0.2760176 0.07283574 0.1305173 -0.2753685 0.07319051 0.1295672 -0.269119 0.06947529 0.1329864 -0.2742352 0.07327121 0.1294128 -0.2742394 0.07418483 0.1286571 -0.2687796 0.07018339 0.1325093 -0.2681045 0.07093757 0.1323218 -0.2730557 0.07438451 0.1289337 -0.2674831 0.07189917 0.1324229 -0.2661461 0.07014906 0.128843 -0.2644402 0.07009369 0.127681 -0.2628747 0.07007354 0.1273577 -0.2617565 0.07006013 0.1274136 -0.2603299 0.0700466 0.1278595 -0.2426285 0.06991469 0.1402826 -0.2415142 0.06991207 0.1419433 -0.2411909 0.06992071 0.1435086 -0.2412466 0.06992936 0.1446267 -0.2417119 0.06999045 0.1460734 -0.2558543 0.07030838 0.1663104 -0.2453242 0.09325993 0.1515033 -0.2555239 0.09356969 0.1660661 -0.2455601 0.0700758 0.1516079 -0.2627153 0.07182788 0.1307319 -0.2617723 0.07181745 0.1309022 -0.2616354 0.07183551 0.1336659 -0.2611219 0.07182508 0.1331005 -0.2611091 0.07181423 0.1315959 -0.2623588 0.07184642 0.1339375 -0.2609317 0.07181739 0.1323488 -0.2631257 0.07185512 0.1338358 -0.2637628 0.07185983 0.133389 -0.2641582 0.07185846 0.1325165 -0.2639638 0.0718494 0.1315759 -0.2634446 0.07183885 0.1310025 -0.2463331 0.07170724 0.1422039 -0.2453905 0.07169675 0.1423739 -0.2452532 0.07171481 0.145138 -0.2447395 0.07170438 0.1445723 -0.2447267 0.07169353 0.1430678 -0.2459765 0.07172566 0.1454095 -0.2445494 0.07169669 0.1438214 -0.2467433 0.07173442 0.1453077 -0.2473802 0.07173913 0.1448614 -0.2477759 0.07173776 0.1439884 -0.2475816 0.0717287 0.1430478 -0.2470622 0.07171815 0.1424744 -0.2666552 0.07453829 0.1373903 -0.2660087 0.07475721 0.136872 -0.264905 0.07545936 0.1365519 -0.2637224 0.07653576 0.1367767 -0.2763469 0.07475429 0.1512281 -0.2766184 0.07497751 0.1519919 -0.2766143 0.07546198 0.1528215 -0.2762945 0.07621419 0.1536899 -0.2757496 0.07701206 0.1543114 -0.2599076 0.0795952 0.1653399 -0.2621902 0.07974302 0.1637583 -0.2597882 0.09384429 0.1652048 -0.2923313 0.07696449 0.1426774 -0.2921241 0.09405153 0.1425613 -0.2592173 0.07746756 0.1633571 -0.2597297 0.07769238 0.1637457 -0.2605323 0.07819747 0.1640414 -0.2614183 0.07893389 0.1640498 -0.2494479 0.07725858 0.1494118 -0.2491697 0.07748985 0.1486009 -0.2492619 0.07823836 0.1474083 -0.2498323 0.07927674 0.1464688 -0.2799335 0.09381133 0.1251502 -0.2801494 0.07669097 0.1252784 -0.247505 0.07909899 0.1481692 -0.2475703 0.09316456 0.1477914 -0.2568704 0.09386938 0.1669687 -0.258207 0.09404176 0.1672067 -0.2593238 0.0938093 0.1670889 -0.2604516 0.09360778 0.1665397 -0.2929602 0.09430891 0.143758 -0.2905241 0.08582007 0.1456075 -0.2902039 0.08685594 0.1458153 -0.2894991 0.08763593 0.1462965 -0.2885811 0.08793008 0.1469345 -0.2876601 0.08767116 0.1475835 -0.2931737 0.07670217 0.1438776 -0.2872459 0.08373248 0.1479357 -0.2867132 0.08469396 0.1482935 -0.2880818 0.08317917 0.1473593 -0.2866021 0.08550053 0.1483586 -0.2888344 0.08313453 0.146833 -0.2867225 0.08640694 0.14826 -0.289476 0.08335894 0.1463803 -0.2870768 0.08709549 0.148001 -0.2901891 0.08411186 0.145869 -0.2904839 0.08495479 0.1456494 -0.2715668 0.07124137 0.1626513 -0.2869651 0.07337915 0.1442396 -0.2874256 0.07369178 0.1452699 -0.2884279 0.07423067 0.1455116 -0.288051 0.07477915 0.1465018 -0.2890162 0.07556641 0.1463659 -0.2772018 0.0731309 0.1302648 -0.2654479 0.07185351 0.1295713 -0.2423143 0.0716784 0.1450815 -0.2455905 0.07174152 0.1482989 -0.2452118 0.07169163 0.1495182 -0.2463837 0.07174378 0.1472391 -0.2608657 0.07179051 0.1286922 -0.2535942 0.07175326 0.1366562 -0.2545748 0.07176846 0.1364573 -0.2641783 0.07183146 0.1286612 -0.2624223 0.07180726 0.1283151 -0.2422133 0.07166242 0.1430297 -0.2555969 0.07179868 0.1391175 -0.2430966 0.07165998 0.1411638 -0.2544898 0.07178717 0.1396983 -0.2534456 0.07177406 0.1393969 -0.2528346 0.07176256 0.1386446 -0.2528362 0.07175379 0.1373975 -0.2559617 0.07179749 0.1382153 -0.255647 0.07178491 0.1370491 -0.2770732 0.07324057 0.1292864 -0.2735857 0.0766927 0.1280669 -0.273603 0.07574427 0.1281919 -0.2763844 0.07371908 0.1282656 -0.2756938 0.07492119 0.1272779 -0.2737813 0.08735787 0.1277613 -0.2747025 0.08761692 0.1271122 -0.2790908 0.09399586 0.1239488 -0.246573 0.09329462 0.1467173 -0.2727234 0.08494859 0.12854 -0.2727735 0.08576208 0.1284921 -0.2730684 0.08660513 0.1282722 -0.2758306 0.08323508 0.1263916 -0.2793128 0.07638943 0.1240805 -0.2763105 0.08379882 0.1260467 -0.2751501 0.08284783 0.1268741 -0.2766053 0.08464157 0.125827 -0.2766554 0.08545523 0.125779 -0.2742033 0.08286601 0.1275368 -0.2733675 0.08341914 0.1281132 -0.2729625 0.08407378 0.1283864 -0.2753588 0.0874508 0.1266553 -0.2760114 0.08698451 0.1262058 -0.2764163 0.08632987 0.1259326 -0.2484573 0.09712284 0.1493508 -0.2586154 0.0973581 0.1637427 -0.2572566 0.09717339 0.1641398 -0.2480139 0.09704303 0.1502885 -0.2470042 0.09654051 0.1509811 -0.2562949 0.09651499 0.1647649 -0.2556279 0.09561204 0.1652684 -0.2462895 0.09569489 0.1515172 -0.2457432 0.09454053 0.1518595 -0.2552273 0.09438174 0.1655461 -0.2449405 0.09360033 0.1499268 -0.2451718 0.09374749 0.148589 -0.2456862 0.0936492 0.1475634 -0.2813741 0.07465177 0.1270059 -0.2808198 0.07499021 0.1262178 -0.2803481 0.07578873 0.1255525 -0.2911815 0.07488298 0.1410135 -0.2917155 0.07524847 0.14178 -0.2921505 0.07605093 0.1424096 -0.2597838 0.07863068 0.1650129 -0.2593073 0.07784241 0.1643877 -0.2800285 0.09674984 0.1253169 -0.2805899 0.09557342 0.1261062 -0.2809225 0.09736627 0.1266 -0.2799924 0.07419514 0.125028 -0.2919548 0.09701907 0.1423507 -0.291927 0.09496855 0.1422895 -0.2926455 0.09580826 0.1433243 -0.2793681 0.09550833 0.1243608 -0.2801369 0.09478813 0.1254509 -0.2914726 0.09576529 0.1416488 -0.2795334 0.07529217 0.124384 -0.2921655 0.07394993 0.1424089 -0.2928542 0.07514363 0.143405 -0.2913685 0.07343965 0.1412654 -0.291046 0.09759467 0.1410591 -0.2909103 0.09612828 0.1408498 -0.2886976 0.09610134 0.1376897 -0.2809417 0.07327181 0.126374 -0.2843612 0.09420317 0.1314774 -0.2876875 0.09427827 0.1362282 -0.2833067 0.09597969 0.1299901 -0.2811144 0.09590917 0.1268587 -0.2590665 0.09367907 0.1655861 -0.2591906 0.07974219 0.1657002 -0.2584044 0.07954007 0.1657571 -0.2582577 0.09386497 0.1656548 -0.2575914 0.07982778 0.1656168 -0.2575601 0.09358853 0.1655586 -0.2569006 0.07959818 0.1651753 -0.2568565 0.09351986 0.1652056 -0.2563042 0.09339278 0.1646246 -0.2585061 0.0958845 0.1635256 -0.2590835 0.09557062 0.1642446 -0.2595562 0.094796 0.1649069 -0.2488531 0.0772745 0.1501731 -0.2478908 0.07834321 0.1482905 -0.247974 0.07776337 0.1489768 -0.2485399 0.07736551 0.1494352 -0.2471562 0.0795964 0.1484419 -0.2466646 0.09327632 0.1489245 -0.2465313 0.09360677 0.1497473 -0.2467084 0.07928115 0.1498191 -0.2466037 0.0934174 0.1505553 -0.2467616 0.07948082 0.1506066 -0.2469332 0.09358996 0.1511785 -0.2471379 0.07933431 0.1513475 -0.2486226 0.09566718 0.1500176 -0.2482977 0.09554427 0.1492774 -0.2477553 0.0951274 0.1488358 -0.2475335 0.09395921 0.1479508 -0.2579885 0.09700387 0.165005 -0.2591811 0.09677803 0.1652772 -0.2580398 0.09608381 0.1662974 -0.2572923 0.09496653 0.1668179 -0.2587149 0.0951811 0.1668526 -0.2571696 0.09648448 0.1655865 -0.2565246 0.09568023 0.1660509 -0.2561166 0.09466975 0.1663525 -0.2599763 0.09466034 0.1666579 -0.2602154 0.0952515 0.1662197 -0.2596327 0.09582477 0.1661733 -0.2898929 0.08339512 0.150727 -0.2909042 0.08312648 0.1500232 -0.2927477 0.08574694 0.148691 -0.2923007 0.08708852 0.1489828 -0.2917308 0.08345746 0.1494392 -0.2916017 0.08773332 0.149462 -0.292221 0.08388215 0.1490893 -0.2926036 0.08472299 0.1488081 -0.2906745 0.08797866 0.1501073 -0.2900766 0.08788239 0.1505275 -0.2893813 0.08732688 0.151023 -0.2889019 0.0865578 0.1513708 -0.288793 0.08520644 0.1514685 -0.2891613 0.08413732 0.1512274 -0.2543619 0.07085317 0.138078 -0.2472772 0.09650939 0.1482756 -0.2466039 0.09553074 0.1475651 -0.2465005 0.09454631 0.1469904 -0.2724373 0.08756709 0.1240598 -0.2735645 0.08726674 0.1232753 -0.2744644 0.08551013 0.1226729 -0.2744492 0.08449232 0.1226997 -0.2737669 0.08700436 0.1231377 -0.2741789 0.08383613 0.1228994 -0.2745358 0.08565747 0.1226207 -0.2735766 0.0830729 0.1233331 -0.2723858 0.08267366 0.1241731 -0.2721077 0.08279234 0.124366 -0.2712534 0.08330088 0.1249561 -0.2706871 0.08423352 0.1253379 -0.2705077 0.08562415 0.1254414 -0.2706353 0.08594632 0.125347 -0.2711444 0.08691561 0.1249753 -0.2721444 0.0876013 0.1242642 -0.2452497 0.09442454 0.1508316 -0.2453853 0.09512096 0.1494119 -0.2462943 0.09604537 0.1487814 -0.2456615 0.09488672 0.1482086 -0.2456577 0.09543496 0.15053 -0.2463027 0.09623926 0.1500657 -0.2471216 0.0967586 0.149484 -0.2618954 0.09730887 0.1501287 -0.262144 0.09731233 0.150184 -0.2621714 0.09730482 0.1490864 -0.2626554 0.09730833 0.1487368 -0.2628417 0.09731251 0.1490029 -0.2799898 0.09746444 0.1406418 -0.2799502 0.09745401 0.1392456 -0.2793761 0.09746581 0.1418966 -0.2623609 0.09730154 0.1483014 -0.2633185 0.09730333 0.146894 -0.2792662 0.0974369 0.1380277 -0.2782496 0.09745788 0.1427226 -0.2618264 0.09731 0.1504064 -0.2780945 0.09741693 0.1372672 -0.2615416 0.0973035 0.1499896 -0.2610239 0.09733486 0.1554287 -0.2613249 0.09734392 0.1560239 -0.2763245 0.09739333 0.1371876 -0.2609364 0.09734231 0.1564733 -0.2618887 0.09729266 0.1478744 -0.2626417 0.09727483 0.1440719 -0.2748996 0.09738379 0.1381519 -0.2742856 0.09738522 0.1394067 -0.2642535 0.09729844 0.1449243 -0.2616373 0.09728533 0.1472827 -0.2614657 0.09728479 0.1475031 -0.2613413 0.09727847 0.1468386 -0.2603452 0.09730035 0.151625 -0.2625346 0.09732598 0.1514179 -0.2683766 0.09740424 0.152263 -0.2768684 0.09744226 0.1429303 -0.2619627 0.09733349 0.1534585 -0.2617233 0.09735548 0.1569548 -0.2626372 0.09736198 0.1562822 -0.264348 0.09737455 0.1550841 -0.2666658 0.09739166 0.153461 -0.2654264 0.09738212 0.1542726 -0.2678849 0.09737944 0.1496407 -0.2752646 0.09741717 0.1423055 -0.2612495 0.09734976 0.1569746 -0.2610292 0.09727162 0.1464142 -0.2670621 0.0973562 0.147814 -0.2609308 0.0972622 0.14527 -0.2661129 0.09738731 0.1537845 -0.2656096 0.09737503 0.1529583 -0.2661701 0.09736913 0.1511601 -0.2607487 0.0972653 0.1460134 -0.2593169 0.09730452 0.1539936 -0.2604896 0.0972594 0.1456434 -0.2602209 0.09726136 0.1463831 -0.2605014 0.09726774 0.1467838 -0.2591106 0.09726774 0.149192 -0.2606426 0.09728324 0.1487156 -0.2610557 0.0972926 0.1493055 -0.2603468 0.09727656 0.148293 -0.2594081 0.0972554 0.1469523 -0.259897 0.09725898 0.1466099 -0.2601775 0.09726536 0.1470106 -0.2596886 0.09726172 0.1473529 -0.2582163 0.09728056 0.1525395 -0.2599477 0.09726756 0.1477231 -0.259149 0.09724956 0.1465822 -0.2651679 0.09737628 0.1539034 -0.2652812 0.09737348 0.1533163 -0.2655892 0.09737932 0.1536025 -0.2586131 0.09724515 0.1468931 -0.265163 0.0973798 0.1544246 -0.2569022 0.09723258 0.1480911 -0.2573937 0.09725731 0.150713 -0.2649081 0.09735912 0.1519542 -0.2639346 0.09734827 0.1521174 -0.2646645 0.09735363 0.1516063 -0.2644156 0.09734803 0.1512508 -0.263075 0.09733814 0.1521897 -0.2642206 0.09734362 0.1509722 -0.2628799 0.09733372 0.151911 -0.2634073 0.09734565 0.1526642 -0.2644035 0.09735679 0.1524973 -0.2636566 0.09735125 0.1530203 -0.2638959 0.09735667 0.153362 -0.2652365 0.09736657 0.1524233 -0.264986 0.09736663 0.1528685 -0.2643992 0.09736275 0.1533274 -0.2639621 0.09733778 0.1506031 -0.2628087 0.09732729 0.1511335 -0.2648468 0.09736973 0.1535423 -0.2647457 0.09737056 0.153849 -0.2659616 0.09733223 0.14636 -0.2743252 0.09739565 0.1408032 -0.2648355 0.09737747 0.154664 -0.2643526 0.09736686 0.1540078 -0.2649366 0.09733647 0.1487272 -0.2636287 0.09733027 0.1501269 -0.2633695 0.09732443 0.1497568 -0.2619873 0.09735542 0.1564908 -0.263156 0.0973196 0.1494518 -0.2617369 0.09734946 0.15609 -0.2626056 0.0973227 0.1508433 -0.2623039 0.09731215 0.1498836 -0.2623686 0.0973103 0.1495155 -0.2623464 0.09731692 0.1504732 -0.2581503 0.07852739 0.1653272 -0.2575564 0.07909166 0.1654372 -0.2575529 0.0780031 0.1645252 -0.257108 0.07852083 0.1647881 -0.2566453 0.07915246 0.164753 -0.2580026 0.07759779 0.1639809 -0.2590214 0.07858633 0.1653493 -0.2585308 0.07785028 0.164629 -0.2503961 0.09567981 0.1531079 -0.2500403 0.09395033 0.1555111 -0.2498664 0.09476596 0.1546139 -0.2533666 0.09402537 0.1602619 -0.2774025 0.09418898 0.1415404 -0.2765198 0.09417724 0.1414258 -0.2758617 0.09416455 0.140787 -0.2756689 0.09415715 0.1400906 -0.2786253 0.09419691 0.1405351 -0.2758218 0.09415405 0.1393844 -0.2785845 0.09418869 0.1394525 -0.2780705 0.09419524 0.141265 -0.2762855 0.09415584 0.13883 -0.2778364 0.09417384 0.1386695 -0.2769535 0.0941621 0.1385547 -0.2557222 0.09580051 0.1607121 -0.2542716 0.09496146 0.1607382 -0.2588208 0.09482175 0.1652336 -0.2579483 0.09485924 0.1652106 -0.256902 0.09484261 0.1646594 -0.2573686 0.09428203 0.1653288 -0.2578045 0.09577351 0.1638419 -0.2565751 0.09417498 0.1648033 -0.2583121 0.09553545 0.1645027 -0.2573579 0.09537196 0.1643927 -0.247461 0.0783751 0.1511662 -0.2481275 0.07759481 0.1507086 -0.2478693 0.07761353 0.1499367 -0.2471581 0.07827889 0.1495597 -0.2473095 0.07851815 0.1487832 -0.2468413 0.07931089 0.1491004 -0.2471348 0.07833302 0.1504313 -0.2469339 0.09456843 0.1503153 -0.2469561 0.09461069 0.1494432 -0.2468491 0.09403437 0.1488603 -0.2474951 0.09459966 0.148401 -0.247079 0.09355252 0.1482672 -0.2478901 0.09532201 0.1505869 -0.2476506 0.0952987 0.1498104 -0.2472662 0.09452509 0.151093 -0.2926825 0.0846762 0.1487537 -0.288828 0.08466786 0.1514525 -0.2893972 0.08367788 0.1510696 -0.290725 0.08808022 0.1500704 -0.2902758 0.08312022 0.1504633 -0.2926667 0.08646041 0.1487364 -0.2886984 0.08586275 0.1515243 -0.2916853 0.08779412 0.1494025 -0.2917248 0.08333837 0.1494453 -0.2893639 0.0874446 0.1510334 -0.2715721 0.08292275 0.124739 -0.2708012 0.08657842 0.1252208 -0.2715324 0.08737838 0.1246963 -0.2741937 0.08658576 0.1228456 -0.273025 0.0827108 0.123725 -0.2704667 0.08484482 0.1254824 -0.2729817 0.08759659 0.1236781 -0.274219 0.08372682 0.122873 -0.2708264 0.08371984 0.1252484 -0.2786644 0.0960437 0.1400569 -0.278481 0.09604644 0.1407558 -0.275808 0.09601306 0.1407158 -0.2779937 0.09604424 0.1412894 -0.2756458 0.09600603 0.1400115 -0.2773146 0.09603756 0.1415354 -0.2758291 0.09600335 0.139313 -0.2764135 0.09602403 0.1413689 -0.2763164 0.09600555 0.1387794 -0.2771921 0.09601324 0.1385081 -0.2780313 0.09602695 0.1388052 -0.2785021 0.09603673 0.1393528 -0.25861 0.09749513 0.1468912 -0.2568991 0.0974825 0.1480894 -0.2626341 0.0976119 0.1562803 -0.2603384 0.09757381 0.1549214 -0.2589034 0.0975461 0.1535234 -0.2579135 0.09752291 0.1519919 -0.2571482 0.09750205 0.1498941 -0.2643449 0.09762454 0.1550824 -0.2593215 0.09752392 0.1496888 -0.2604912 0.09755373 0.1518362 -0.2623548 0.09759092 0.1538282 -0.2609277 0.09751218 0.1452682 -0.2626386 0.09752482 0.1440702 -0.2666627 0.09764164 0.1534593 -0.2659534 0.09761285 0.15066 -0.2647844 0.09758305 0.1485124 -0.2629204 0.09754574 0.1465212 -0.2683736 0.09765422 0.1522613 -0.264934 0.0975629 0.1454288 -0.2663689 0.09759062 0.1468266 -0.2673588 0.09761381 0.1483582 -0.268124 0.09764182 0.1504552 -0.2654233 0.09763211 0.1542708 -0.2661156 0.09763687 0.1537238 -0.2648187 0.09762746 0.1546614 -0.2642977 0.097615 0.153831 -0.264502 0.09761303 0.1531888 -0.2650746 0.09761756 0.1528431 -0.2655764 0.09762454 0.1529585 -0.265173 0.09763002 0.1544244 -0.265589 0.0976293 0.1535962 -0.265275 0.09762346 0.1533233 -0.2648047 0.09761941 0.1535684 -0.2647728 0.09762167 0.1539413 -0.2651648 0.09762626 0.1539016 -0.2652334 0.09761655 0.1524215 -0.264905 0.0976091 0.1519525 -0.2639315 0.09759825 0.1521156 -0.2646614 0.09760361 0.1516045 -0.2644125 0.09759801 0.1512491 -0.2630719 0.09758812 0.1521879 -0.2634042 0.09759563 0.1526623 -0.2644004 0.09760677 0.1524956 -0.2636535 0.09760123 0.1530185 -0.2638928 0.09760665 0.1533603 -0.2626184 0.09757786 0.1515401 -0.263959 0.09758776 0.1506013 -0.2628768 0.09758371 0.1519092 -0.2642175 0.0975936 0.1509703 -0.2623434 0.09756684 0.1504714 -0.2633665 0.09757441 0.149755 -0.2621409 0.09756231 0.1501822 -0.2618234 0.09755992 0.1504046 -0.2624881 0.09757494 0.1513541 -0.2628057 0.09757727 0.1511317 -0.2626025 0.09757268 0.1508415 -0.2636255 0.09758025 0.1501251 -0.262167 0.0975548 0.1490852 -0.2628386 0.09756249 0.1490011 -0.2626523 0.09755825 0.148735 -0.2623932 0.09755241 0.1483649 -0.2610526 0.09754258 0.1493037 -0.2623611 0.09756022 0.1495129 -0.262325 0.09756213 0.1498431 -0.2619848 0.0975598 0.1501046 -0.2615891 0.09755456 0.1500468 -0.2631529 0.09756958 0.14945 -0.2620193 0.09754401 0.1478308 -0.261752 0.09754127 0.1479145 -0.2614626 0.09753477 0.1475013 -0.2616342 0.09753531 0.1472809 -0.261378 0.09752953 0.1469148 -0.2603437 0.09752655 0.1482912 -0.2606396 0.09753322 0.1487138 -0.2623019 0.09755039 0.1482345 -0.2610261 0.0975216 0.1464124 -0.2604983 0.09751772 0.146782 -0.2602178 0.09751135 0.1463813 -0.2607456 0.09751522 0.1460117 -0.2604865 0.09750938 0.1456417 -0.2591459 0.09749954 0.1465803 -0.259405 0.09750539 0.1469505 -0.2598939 0.09750896 0.1466081 -0.2601744 0.09751534 0.1470088 -0.2596855 0.0975117 0.1473512 -0.2599446 0.09751754 0.1477213 -0.2612852 0.09752744 0.1467825 -0.2619722 0.09760504 0.1564646 -0.261747 0.09760576 0.1569486 -0.2612149 0.0975992 0.1569565 -0.260938 0.09759205 0.156431 -0.2613564 0.09759426 0.1560134 -0.2617594 0.09759986 0.1561056 -0.2889723 0.08326512 0.1494203 -0.2899415 0.08303004 0.1487454 -0.2878656 0.08632838 0.1501468 -0.2878 0.08512729 0.1502116 -0.2881994 0.08402198 0.1499494 -0.2883812 0.08734947 0.1497696 -0.2892284 0.08795666 0.1491667 -0.2902137 0.08801114 0.1484761 -0.2909377 0.08763355 0.1479752 -0.29146 0.0870651 0.1476185 -0.2918012 0.08619856 0.1473932 -0.2918865 0.08535331 0.1473469 -0.2916732 0.08443409 0.1475108 -0.2912783 0.08373767 0.1477981 -0.2906179 0.08322763 0.1482686 -0.2744833 0.08300065 0.1246528 -0.2737406 0.08269953 0.1251775 -0.2714243 0.08571445 0.1267517 -0.2730438 0.08270573 0.1256653 -0.271398 0.08475738 0.1267852 -0.2716704 0.08650785 0.1265668 -0.2721467 0.08321654 0.1262854 -0.2723723 0.08734613 0.1260622 -0.2716462 0.08395999 0.126624 -0.2731148 0.08764719 0.1255375 -0.2738118 0.087641 0.1250496 -0.2747088 0.08713006 0.1244294 -0.2753126 0.08617097 0.124022 -0.2754746 0.08523207 0.1239234 -0.2753919 0.08438867 0.1239947 -0.2750041 0.0835601 0.1242793 -0.2617881 0.0975542 0.1496536 -0.2619015 0.09755277 0.1492621 -0.2616092 0.09755063 0.1494655 -0.2620021 0.09755563 0.1494868 -0.2613977 0.09753769 0.1480263 -0.2612335 0.097534 0.1477918 -0.2609184 0.09753292 0.1481839 -0.261198 0.09759783 0.1567961 -0.2618656 0.09760439 0.1565577 -0.2612543 0.09759426 0.156191 -0.2615607 0.09760302 0.1568919 -0.2616168 0.09759837 0.1561444 -0.2610791 0.09759396 0.1564539 -0.3039245 0.07747638 0.1390429 -0.3044791 0.07790946 0.1386477 -0.3017971 0.07832992 0.140519 -0.3025007 0.07748401 0.1400397 -0.3058675 0.08101272 0.1376267 -0.3016048 0.08338022 0.1405737 -0.3019928 0.08452504 0.1402841 -0.3066241 0.08420807 0.1370463 -0.3068202 0.08753144 0.1368566 -0.3017189 0.08629184 0.1404479 -0.3013347 0.08690053 0.1407071 -0.3013727 0.09092903 0.140617 -0.3009348 0.09044361 0.1409313 -0.300796 0.08723145 0.1410793 -0.3013331 0.09159868 0.1406341 -0.3065618 0.09695923 0.1368738 -0.3000973 0.0873242 0.1415669 -0.3010051 0.09197282 0.1408579 -0.2987018 0.09059792 0.1424922 -0.2979167 0.08719354 0.1430957 -0.2967884 0.09025716 0.1438374 -0.2964513 0.0866248 0.1441308 -0.2919919 0.08185827 0.1473283 -0.2949888 0.0855509 0.1451717 -0.2910404 0.08128023 0.1480036 -0.2997987 0.09537959 0.1416488 -0.2988111 0.09220367 0.1423904 -0.2896459 0.08102244 0.1489841 -0.2949785 0.08943736 0.1451175 -0.2997181 0.09713131 0.1415816 -0.2931128 0.0880059 0.1464464 -0.2884269 0.08139806 0.1498315 -0.2925639 0.08812308 0.1468288 -0.2965653 0.09184211 0.1439685 -0.2872346 0.08233553 0.1506516 -0.2922677 0.08870637 0.147027 -0.2924093 0.08929598 0.1469185 -0.2953828 0.09486061 0.1447487 -0.2944389 0.09090322 0.1454721 -0.286519 0.08360093 0.1511326 -0.2861288 0.08526217 0.1513796 -0.2926454 0.09375739 0.1466827 -0.28643 0.08739495 0.151135 -0.2901417 0.09202152 0.1484632 -0.2874668 0.08911865 0.1503819 -0.2834091 0.09496349 0.1182144 -0.2834104 0.09683507 0.1182928 -0.2901766 0.09682339 0.113481 -0.2846783 0.09156841 0.1173794 -0.2850111 0.0909518 0.117156 -0.2904182 0.0871613 0.1134302 -0.2848335 0.09031218 0.1172906 -0.2824091 0.09183359 0.118964 -0.2818468 0.09491872 0.1193089 -0.2849742 0.08648717 0.1172525 -0.2853274 0.08588469 0.1170147 -0.2844464 0.08684396 0.1176164 -0.2844588 0.09006577 0.1175568 -0.2801634 0.09147197 0.120542 -0.2789808 0.09449046 0.1213223 -0.2837384 0.08694499 0.1181104 -0.2855862 0.08452689 0.116855 -0.2902221 0.08383792 0.11362 -0.2822998 0.09022778 0.1190658 -0.2816851 0.08685922 0.1195495 -0.2852458 0.08302718 0.117117 -0.2894655 0.08064258 0.1142002 -0.2780369 0.09053313 0.1220457 -0.2762433 0.09338724 0.1232564 -0.2803864 0.08988702 0.1204109 -0.2800493 0.08625471 0.1207043 -0.2785765 0.08906728 0.1216911 -0.2875224 0.07710623 0.1156166 -0.2880771 0.07753926 0.1152213 -0.2862331 0.07708185 0.1165197 -0.2760541 0.08898222 0.1234585 -0.2737397 0.09165138 0.1250367 -0.2786439 0.08524751 0.1217044 -0.2856882 0.07747679 0.116895 -0.2853657 0.07811307 0.1171107 -0.2767283 0.08764314 0.1230075 -0.2761278 0.087767 0.1234262 -0.2758646 0.08849006 0.1235989 -0.271566 0.08934962 0.126595 -0.2755899 0.08148813 0.1239019 -0.2702936 0.08760327 0.1275134 -0.2746384 0.08091008 0.1245772 -0.2697472 0.08578717 0.1279247 -0.2732439 0.08065235 0.1255577 -0.2699312 0.08372831 0.1278284 -0.2715427 0.08129352 0.1267386 -0.2706013 0.08231592 0.1273816 -0.2616123 0.09730064 0.1494672 -0.2617589 0.09730368 0.1496443 -0.2619004 0.09730273 0.1492655 -0.2620123 0.09730577 0.1494995 -0.2609207 0.09728294 0.1481856 -0.2614008 0.09728771 0.1480281 -0.2612366 0.09728401 0.1477936 -0.2617447 0.09735071 0.1562484 -0.2618383 0.09735393 0.1565408 -0.2616887 0.09735411 0.1568291 -0.2613774 0.09735071 0.1568904 -0.2610949 0.09734517 0.1566061 -0.2611079 0.0973435 0.1563442 -0.2614515 0.09734618 0.1561242 -0.3010581 0.08733582 0.1428474 -0.3017661 0.08723479 0.1423533 -0.3022939 0.08687794 0.1419894 -0.3026469 0.08627575 0.1417518 -0.302594 0.08349579 0.1418327 -0.3029058 0.08491766 0.141592 -0.30271 0.07833272 0.1418331 -0.3034784 0.07748091 0.1413085 -0.3047533 0.0774849 0.1404159 -0.305348 0.07784587 0.1399937 -0.3067851 0.0810334 0.1389372 -0.3075417 0.08422875 0.138357 -0.3077378 0.08755213 0.1381672 -0.3060003 0.09869146 0.1361432 -0.3070096 0.09907788 0.1375996 -0.3061198 0.1004844 0.1363872 -0.3052402 0.09942013 0.1350882 -0.3063752 0.09782552 0.1366429 -0.3074695 0.09721004 0.1381797 -0.3051812 0.1010397 0.1350702 -0.3028873 0.09944558 0.1317307 -0.3028446 0.101045 0.1317353 -0.2992559 0.09841185 0.1409744 -0.2984557 0.09923696 0.1398658 -0.2998918 0.099541 0.1419281 -0.3003876 0.09834325 0.1425868 -0.2824791 0.09498876 0.1169118 -0.2824775 0.09671425 0.1169564 -0.2990981 0.1004633 0.1408331 -0.2827652 0.09833163 0.1174331 -0.2838463 0.09814977 0.1189689 -0.2835434 0.09983414 0.1186055 -0.2846158 0.09894597 0.1200997 -0.2845726 0.1005589 0.120104 -0.3007287 0.09535431 0.1429514 -0.3006482 0.09712475 0.1429088 -0.298373 0.1008601 0.1398143 -0.2991664 0.09530955 0.1440459 -0.2963004 0.09488129 0.1460593 -0.293563 0.09377807 0.1479934 -0.2910593 0.0920422 0.1497737 -0.2888857 0.08974045 0.151332 -0.2876132 0.08799415 0.1522504 -0.2871939 0.08680158 0.1525627 -0.2870613 0.08508688 0.1526829 -0.2876808 0.0830484 0.1522812 -0.2890031 0.08158648 0.1513786 -0.2907245 0.08103591 0.150182 -0.291958 0.08130091 0.1493142 -0.293006 0.08196514 0.14857 -0.2960422 0.08570176 0.1463853 -0.2990046 0.08725005 0.1442865 -0.2973689 0.08664554 0.1454412 -0.3019254 0.09199935 0.1421665 -0.3022219 0.09166353 0.1419643 -0.3023229 0.09118926 0.1419009 -0.3021763 0.09075105 0.1420106 -0.3018271 0.09045922 0.1422597 -0.2958961 0.0894581 0.1464281 -0.2940479 0.08803397 0.1477446 -0.297706 0.09027785 0.1451479 -0.2996194 0.09061861 0.1438028 -0.2934474 0.08815777 0.1481629 -0.2931842 0.08888077 0.1483359 -0.2933828 0.08938735 0.1481888 -0.2953565 0.09092396 0.1467826 -0.2974829 0.09186279 0.145279 -0.2997287 0.09222441 0.143701 -0.2834764 0.08684062 0.1163423 -0.2827777 0.08693331 0.1168299 -0.2840151 0.0865097 0.1159702 -0.2843994 0.08590078 0.1157109 -0.2805972 0.08680272 0.1183587 -0.2791317 0.08623397 0.1193938 -0.2777571 0.08523601 0.120372 -0.2747691 0.08155387 0.1225222 -0.2691104 0.08700418 0.126398 -0.2701466 0.08872711 0.1256453 -0.2688091 0.08487129 0.1266426 -0.2693905 0.08271253 0.1262696 -0.2707656 0.08117508 0.1253312 -0.2724873 0.08062434 0.1241344 -0.2737208 0.0808894 0.1232666 -0.2780632 0.09446978 0.1200118 -0.2753258 0.09336656 0.1219457 -0.2728221 0.09163069 0.1237262 -0.2905952 0.09825783 0.1141372 -0.2913215 0.09909528 0.115208 -0.2913354 0.1007273 0.1152946 -0.2937113 0.09923851 0.118625 -0.2936687 0.100838 0.1186296 -0.290427 0.1001301 0.1139737 -0.2896136 0.09868532 0.1127536 -0.2892537 0.09679937 0.1121627 -0.2895006 0.08714061 0.1121196 -0.2871939 0.07756626 0.1138859 -0.2885479 0.08062183 0.1128897 -0.2893045 0.08381718 0.1123094 -0.2866591 0.07710456 0.1142677 -0.2844436 0.07808226 0.1158034 -0.2848067 0.07741433 0.1155598 -0.2853679 0.07704693 0.1151726 -0.2842852 0.08298939 0.1158367 -0.2846732 0.08413422 0.1155471 -0.2836882 0.09158784 0.1161189 -0.2840311 0.09116256 0.1158856 -0.2840553 0.09058535 0.1158778 -0.2836623 0.09005802 0.1161613 -0.2814915 0.09181284 0.1176534 -0.2771193 0.09051239 0.1207351 -0.2792458 0.09145128 0.1192315 -0.2757933 0.08761507 0.1217094 -0.2749482 0.08831524 0.12229 -0.2752438 0.08773255 0.1220922 -0.275098 0.08892101 0.1221755 -0.2776589 0.08904653 0.1203805 -0.2794688 0.08986634 0.1191004 -0.2813823 0.09020704 0.1177553 -0.2615811 0.09734892 0.1562885 -0.2615619 0.09735143 0.156672 -0.2615063 0.09734934 0.1564719 -0.2613674 0.09734958 0.1567457 -0.2927297 0.08734774 0.1486782 -0.2921127 0.08804321 0.1490994 -0.2912505 0.08851462 0.1496956 -0.2931244 0.08629965 0.1484186 -0.2932014 0.0852192 0.1483817 -0.2904143 0.08853983 0.1502807 -0.2895179 0.08819758 0.1509137 -0.2928333 0.08391875 0.14866 -0.2886613 0.08720982 0.151529 -0.2919767 0.0829308 0.1492753 -0.2910803 0.08258855 0.1499084 -0.2882825 0.08584481 0.1518158 -0.2902442 0.08261376 0.1504933 -0.2884683 0.08441561 0.1517083 -0.2891764 0.08324944 0.151231 -0.3064621 0.1027631 0.1291754 -0.3079383 0.1022915 0.1281493 -0.3066859 0.100943 0.1290475 -0.3074796 0.1041764 0.128442 -0.3090785 0.1044175 0.1273034 -0.3053694 0.1018452 0.1299549 -0.3046893 0.09974092 0.1304644 -0.3039355 0.1011871 0.1309692 -0.2736451 0.0824576 0.1232949 -0.2745364 0.08339869 0.1226559 -0.2749049 0.08445239 0.1223813 -0.2724936 0.08213382 0.1241061 -0.2749552 0.08553397 0.1223289 -0.2716734 0.08234149 0.1246772 -0.274555 0.08682882 0.1225887 -0.2708576 0.08292436 0.1252391 -0.2738755 0.08763164 0.1230518 -0.2701916 0.08412641 0.1256865 -0.273118 0.08807247 0.1235752 -0.2700566 0.08556365 0.1257582 -0.2704837 0.08690661 0.125438 -0.2721771 0.08812832 0.1242331 -0.2713751 0.08784776 0.1247989 -0.2949943 0.1010673 0.1176979 -0.2953683 0.09952956 0.1174603 -0.2968591 0.1002514 0.1164052 -0.296317 0.1017201 0.1167614 -0.2986244 0.1018348 0.1151441 -0.2973398 0.1026142 0.1160312 -0.2998488 0.1040598 0.11426 -0.2983902 0.1041271 0.1152842 -0.2615539 0.0976004 0.1565395 -0.2615337 0.09760135 0.1567029 -0.2613706 0.09759968 0.1567483 -0.2617212 0.09760218 0.1564962 -0.2614581 0.09759849 0.1564385 -0.2615781 0.09759891 0.1562867 -0.2611803 0.09759551 0.1564975 -0.2915228 0.08855587 0.1506029 -0.2906875 0.08851832 0.1511886 -0.29373 0.08522897 0.1491102 -0.2924274 0.08822691 0.1499748 -0.2932897 0.08382183 0.1494407 -0.2930782 0.08757859 0.1495295 -0.2935575 0.08666104 0.1492084 -0.2923984 0.08288079 0.1500796 -0.2915965 0.08260023 0.1506456 -0.2906557 0.08265602 0.1513034 -0.2896111 0.08334738 0.1520237 -0.2891048 0.08416581 0.1523654 -0.288806 0.08525913 0.1525573 -0.2888686 0.08627617 0.1524974 -0.289237 0.08732968 0.1522227 -0.289837 0.08803427 0.1517916 -0.3073745 0.107261 0.1263529 -0.3012363 0.1077845 0.1175189 -0.3065754 0.1078574 0.125145 -0.3004142 0.1073386 0.116373 -0.2995774 0.1062756 0.1154473 -0.3078461 0.1061438 0.1273945 -0.2989162 0.1051093 0.1151629 -0.3078025 0.1051469 0.1279852 -0.3079064 0.1078433 0.1242541 -0.3092324 0.1058775 0.1266118 -0.3087693 0.1071418 0.1255602 -0.3023448 0.1077143 0.1163108 -0.3014227 0.1069983 0.115063 -0.3007907 0.1060311 0.1144278 -0.3002822 0.1050301 0.1141741 -0.2726739 0.08223068 0.1228797 -0.2717346 0.082161 0.1235384 -0.2744514 0.0855242 0.1215831 -0.2737013 0.08293759 0.1221491 -0.2739766 0.08692443 0.1218934 -0.2743144 0.08408981 0.1217017 -0.2733594 0.08762001 0.1223146 -0.2724972 0.08809143 0.1229108 -0.2713141 0.08805131 0.1237397 -0.2702866 0.08734452 0.1244703 -0.2698008 0.086519 0.1248235 -0.2695291 0.08542144 0.125031 -0.2696169 0.08440554 0.1249857 -0.2700113 0.08335763 0.1247261 -0.270926 0.08242964 0.1241003 -0.2613649 0.09759867 0.1566196 -0.2614789 0.0975998 0.1565814 -0.2614809 0.09734982 0.1565879 -0.261368 0.09734785 0.1565055 -0.2613889 0.09734904 0.1566317 -0.3208263 0.07199496 0.087233 -0.3232603 0.07199496 0.08489507 -0.3220181 0.06899499 0.0862289 -0.3179034 0.07199496 0.08892053 -0.3192125 0.06899499 0.08828032 -0.315988 0.06899499 0.08957743 -0.3146617 0.07199496 0.08985954 -0.3125434 0.06899499 0.0900402 -0.2989686 0.07199496 0.07993584 -0.3002915 0.06899499 0.08304077 -0.2989408 0.06899499 0.07983839 -0.3002915 0.07199496 0.08304077 -0.3112894 0.07199496 0.08999538 -0.3090909 0.06899499 0.08964025 -0.2984272 0.07199496 0.07660454 -0.2984205 0.06899499 0.07640194 -0.3079825 0.07199496 0.0893203 -0.3058433 0.06899499 0.08840209 -0.2986988 0.07199496 0.07324045 -0.2987628 0.06899499 0.07294327 -0.2997676 0.07199496 0.07003909 -0.2999466 0.06899499 0.0696755 -0.3049333 0.07199496 0.08787345 -0.3036689 0.06899499 0.08697193 -0.3023191 0.07199496 0.08573895 -0.3017967 0.06899499 0.08516401 -0.3015714 0.07199496 0.06718659 -0.3018989 0.06899499 0.06679999 -0.3040055 0.07199496 0.0648486 -0.3044993 0.06899499 0.06449401 -0.3069283 0.07199496 0.06316107 -0.3075877 0.06899499 0.0628997 -0.3101701 0.07199496 0.06222212 -0.3109736 0.06899499 0.06211531 -0.3135424 0.07199496 0.06208622 -0.3144484 0.06899499 0.06218916 -0.3168492 0.07199496 0.0627613 -0.317798 0.06899499 0.06311666 -0.3198984 0.07199496 0.06420814 -0.3208158 0.06899499 0.06484073 -0.3225127 0.07199496 0.06634265 -0.3233159 0.06899499 0.06725513 -0.3245403 0.07199496 0.06904077 -0.3251443 0.06899499 0.07021093 -0.3258631 0.07199496 0.07214576 -0.3261882 0.06899499 0.07352608 -0.3264045 0.07199496 0.07547706 -0.3263832 0.06899499 0.0769962 -0.326133 0.07199496 0.07884114 -0.3257175 0.06899499 0.08040744 -0.3250642 0.07199496 0.08204251 -0.3242319 0.06899499 0.08354955 + + + + + + + + + + -0.5875762 0.5338495 0.6080782 -0.5375391 0.5656449 0.6253781 -0.173866 0.8301497 0.5297378 -0.2439348 0.9378457 0.2468626 -0.1836229 0.8040283 0.5655274 -0.282016 0.8998216 0.3328487 0.1654571 0.190071 0.9677278 -0.7337777 0.05717617 0.6769796 -0.2863118 0.1314297 0.9490795 -0.3743512 0.1564665 0.913991 0.1197792 0.230332 0.9657122 0.09349715 0.1839917 0.978471 -7.5008e-4 0.5672606 0.823538 -0.7866054 0.1291078 0.6038072 -0.7597764 0.1369388 0.6356003 -0.4269763 0.3910632 0.8153287 0.001725673 0.5658879 0.8244804 -0.4268596 0.3910655 0.8153887 9.26157e-4 0.5640038 0.8257716 -0.1565179 0.8277558 0.5388158 -0.7859669 0.2181779 0.5784931 -0.7917128 -1.02742e-4 0.6108936 -0.7751199 2.57403e-4 0.6318142 -0.4264501 -0.001226127 0.9045103 -0.2362065 8.23125e-4 0.9717026 -0.2769097 1.70388e-4 0.960896 0.1574233 -1.61932e-4 0.9875312 0.182498 1.27475e-4 0.9832062 0.4942865 0.1120434 0.8620483 0.4696487 0.3304448 0.8186796 0.4951916 0.09838193 0.8631954 0.4669842 0.3442535 0.8145032 0.4213674 0.5318762 0.7345457 0.4274577 0.5108221 0.7458826 0.3516589 0.7070651 0.6135104 0.3458389 0.7189782 0.6028813 0.2646549 0.8468344 0.4613345 0.164355 0.9438838 0.2864798 0.2707411 0.8387633 0.4724144 0.0555498 0.9937044 0.09729248 0.1536411 0.950946 0.268507 0.05262166 0.9943351 0.09235173 -0.8573713 0.1508353 0.4921008 -0.8618842 0.112733 0.4944158 -0.6985381 0.5925115 0.4012164 -0.7358244 0.5295021 0.4221256 -0.5923849 0.7303384 0.3401265 -0.4535512 0.8525608 0.259676 -0.295464 0.940117 0.1699445 -0.8674969 -2.96854e-5 0.4974427 -0.8675444 0 0.4973598 -0.8676565 3.02902e-4 0.497164 -0.8674018 -2.60419e-4 0.4976083 -0.8669632 -2.02063e-4 0.4983721 -0.8671503 1.26755e-5 0.4980468 -0.867305 -3.25268e-5 0.4977774 -0.8672805 0 0.4978199 -0.8672813 0 0.4978185 -0.8671756 3.20299e-5 0.4980027 -0.8680317 -9.3772e-4 0.496508 -0.8674085 1.69869e-4 0.4975968 -0.8674156 2.88293e-4 0.4975844 -0.8671715 8.16251e-4 0.4980092 -0.8674088 -3.81425e-4 0.4975962 -0.4504594 -0.2297545 0.8627278 0.05179184 -0.3692732 0.9278766 -0.3941125 -0.2776186 0.8761298 0.1626322 -0.09891152 0.9817165 0.004511535 -0.4042102 0.9146552 0.08864343 -0.1507266 0.9845933 -0.6897988 -0.5162237 0.5076325 -0.8106517 -0.2104681 0.5463947 -0.3585178 -0.8441318 0.3986309 -0.5953187 -0.6036445 0.5302914 -0.2050271 -0.8973426 0.3908201 -0.2613244 -0.8952031 0.3610002 -0.07277005 -0.7165158 0.6937649 -0.7867054 -0.1354489 0.6022858 -0.7769242 -0.1746805 0.6048764 -0.4786134 -0.4947149 0.7253871 -0.07295823 -0.7160095 0.6942676 -0.4785639 -0.4948328 0.7253394 0.06156122 -0.3895164 0.91896 -0.07514578 -0.7167536 0.6932657 -0.7376792 -0.1123291 0.6657414 0.4973907 5.46251e-7 0.8675267 0.4973371 6.91752e-5 0.8675574 -2.21671e-4 1 1.27176e-4 -6.13335e-4 0.9999998 1.37807e-4 -0.7729738 0.3741528 -0.5123682 -0.8164958 0.1394019 -0.5602694 -0.7864079 0.5162494 0.3391891 -0.8809078 0.2103151 0.4239918 -0.5274116 0.8425278 0.1094709 -0.7582319 0.603742 0.2461302 -0.4405731 0.897346 -0.02579641 -0.4435337 0.8952609 0.04225975 -0.6382744 0.7140126 -0.2877357 -0.9172953 0.1315087 0.3758653 -0.9143555 0.1747251 0.3652741 -0.8677206 0.4948319 0.04693025 -0.6361836 0.7159923 -0.2874464 -0.8677651 0.494752 0.04694926 -0.76226 0.38943 -0.5170145 -0.6364178 0.7167517 -0.2850254 -0.9497153 0.1109125 0.2928127 -0.9701752 0.2351382 -0.05890893 -0.9558309 0.274999 -0.103744 -0.7725309 0.3730215 -0.5138591 -0.857596 -0.1509054 0.4916877 -0.861902 -0.1124473 0.4944498 -0.6989139 -0.5925959 0.4004366 -0.735853 -0.5294613 0.4221269 -0.5926638 -0.7303124 0.3396965 -0.4560139 -0.8505123 0.2620695 -0.2420955 -0.9603682 0.1381403 -0.8111845 -0.5656521 0.1483829 -0.8214931 -0.5339164 0.2002062 -0.5450435 -0.830159 -0.1173191 -0.5467302 -0.8289846 -0.1177737 -0.441854 -0.8922752 0.09279131 -0.9949766 -0.09711426 -0.02429902 -0.950495 -0.07052743 0.3026304 -0.8619435 -0.1673201 -0.4785994 -0.9771646 -0.1637403 -0.1354201 -0.7694435 -0.2370061 -0.5931146 -0.7979639 -0.1829273 -0.5742747 -0.7107194 -0.5656425 -0.4182423 -0.9179143 -0.1301756 0.3748169 -0.9325391 -0.137971 0.3336688 -0.9193657 -0.3910497 -0.04297548 -0.710807 -0.5659139 -0.4177258 -0.9193693 -0.3910354 -0.04302811 -0.7124529 -0.5638729 -0.4176822 -0.5441027 -0.8277931 -0.1367883 -0.8961393 -0.2183067 0.386363 -0.9325889 4.83136e-4 0.36094 -0.917793 -2.5261e-5 0.3970592 -0.9935841 8.83792e-4 -0.1130926 -0.999311 1.24298e-5 -0.03711581 -0.9556576 5.59896e-4 -0.2944796 -0.8795171 -8.82032e-4 -0.4758666 -0.7200567 0.001333475 -0.6939141 -0.4945077 0.1100778 -0.8621746 -0.496551 0.1232987 -0.8592058 -0.4741684 0.3461523 -0.8095325 -0.4730677 0.3384423 -0.8134272 -0.4204687 0.556338 -0.7167246 -0.4926259 0.1531246 -0.8566637 -0.5163072 -6.32263e-4 -0.8564033 -0.4963435 -1.27536e-4 -0.8681262 -0.4975164 -0.003421843 -0.8674479 -0.4987248 0.004606008 -0.8667482 -0.4984982 0.003380239 -0.8668842 -0.4973742 4.66902e-5 -0.8675361 -0.4968438 -0.001136422 -0.8678393 -0.4145356 -0.5566267 -0.7199494 -0.4768692 -0.3429391 -0.8093137 -0.4753925 -0.3247507 -0.8176424 -0.4942125 -0.1103227 -0.8623125 -0.4965359 -0.1249715 -0.8589727 -0.5052114 -0.02334064 -0.86268 -0.4999981 3.99599e-6 -0.8660266 1.92504e-6 -1 4.51351e-6 -3.58412e-7 -1 0 0 -1 0 8.06408e-6 -1 0 -2.03053e-7 -1 0 0 -1 0 -1.70548e-5 -1 0 -6.03206e-6 -1 0 1.64727e-7 -1 0 2.24764e-7 -1 1.36784e-5 2.988e-7 -1 0 4.07528e-7 -1 0 6.154e-7 -1 0 -1.42327e-5 -1 6.74895e-6 -3.82538e-7 -1 -2.29111e-6 -3.0243e-7 -1 -1.1481e-5 -2.47004e-7 -1 -4.63137e-6 -2.0163e-7 -1 3.83414e-7 0 -1 -2.92528e-7 0 -1 -1.30543e-6 0 -1 8.81951e-6 0 -1 -3.36497e-6 0 -1 3.29527e-7 1.24788e-7 -1 -2.06345e-6 -2.36123e-7 -1 -1.67913e-5 0 -1 5.05104e-7 6.9291e-7 -1 0 1.32048e-6 -1 -6.48004e-5 2.7729e-7 -1 2.82987e-6 1.88567e-7 -1 0 0.5000022 0 0.8660242 0.5000017 0 0.8660244 0 1 0 0 1 -3.37631e-7 0 1 5.50249e-6 0 1 4.12881e-7 0 1 -8.665e-6 0 1 -8.96072e-6 0 1 2.10873e-5 0 1 -2.15366e-5 0 1 8.07793e-6 0 1 -8.54908e-7 0 1 -1.01882e-5 0 1 -8.48242e-6 0 1 6.71644e-6 0 1 -9.04682e-7 0 1 -3.2108e-6 0 1 3.06113e-6 -0.4999992 0 -0.866026 -0.5000005 0 -0.8660252 0.4942424 -0.1120308 0.8620752 0.4942881 -0.1113767 0.8621338 0.4725926 -0.3130476 0.8238068 0.4694049 -0.330428 0.8188262 0.4171701 -0.5445324 0.7276356 0.4213733 -0.5318642 0.734551 0.3577591 -0.6950393 0.6236416 0.3516358 -0.7070801 0.6135063 0.2546781 -0.8587369 0.4446463 0.2646636 -0.8468323 0.4613333 0.1697384 -0.9400198 0.2958914 0.1642146 -0.943879 0.2865769 0.03431558 -0.9975437 0.06106644 0.05574566 -0.9937042 0.09718251 -0.4942967 0.1119403 -0.8620558 -0.4744724 0.3013038 -0.8270987 -0.470152 0.3302602 -0.8184653 -0.4175468 0.5445255 -0.7274248 -0.4213179 0.5320324 -0.7344609 -0.357789 0.6949871 -0.6236827 -0.3521406 0.7069595 -0.6133559 -0.2544724 0.8597236 -0.4428535 -0.1715302 0.9388455 -0.2985744 -0.264676 0.8468065 -0.4613735 -0.03531098 0.9974807 -0.06152588 -0.1643717 0.9438627 -0.28654 -0.05625641 0.9937078 -0.09685081 -5.01788e-4 -0.9999999 2.87969e-4 -0.001087665 -0.9999994 3.03402e-4 -0.4944581 -0.1120012 -0.8619553 -0.4969211 -0.06995624 -0.8649715 -0.4698013 -0.3303181 -0.8186432 -0.4677556 -0.3410821 -0.8153942 -0.4213055 -0.5321166 -0.734407 -0.4275766 -0.5124742 -0.7446802 -0.3521348 -0.7069905 -0.6133233 -0.3458753 -0.718918 -0.6029322 -0.2646749 -0.8467896 -0.4614053 -0.2711066 -0.8387952 -0.4721482 -0.1648537 -0.9438621 -0.2862651 -0.149938 -0.9535262 -0.2613552 -0.05555373 -0.9937103 -0.09723079 -0.4980961 -6.39886e-7 -0.8671219 -0.4985397 5.67634e-4 -0.8668667 -0.659714 0 -0.7515168 -0.6601374 -1.4833e-5 -0.7511451 -0.6601344 0 -0.7511475 -0.6601292 0 -0.7511521 -0.6595304 -1.42279e-4 -0.751678 -0.6601249 -7.0541e-5 -0.7511558 -0.6601316 8.75543e-6 -0.75115 -0.6591807 0.004850625 -0.7519691 -0.6601461 2.65894e-5 -0.7511373 -0.6601197 7.45495e-6 -0.7511605 -0.6602843 4.09198e-4 -0.7510157 -0.6599512 0.01826918 -0.7510865 -0.6601338 -2.18286e-6 -0.7511482 -0.6601235 8.91498e-6 -0.7511572 -0.6595562 -0.006064593 -0.7516309 -0.6600304 1.52558e-4 -0.7512389 -0.6600095 1.21066e-4 -0.7512574 -0.6601354 0 -0.7511467 -0.6608241 -0.009891331 -0.7504757 -0.660133 -8.5774e-6 -0.7511488 -0.6601374 1.4833e-5 -0.7511451 -0.66012 -7.45498e-6 -0.7511602 -0.660135 4.36571e-6 -0.751147 -0.6601221 -6.48361e-6 -0.7511584 -0.6603254 -5.14452e-4 -0.7509796 -0.6601348 0 -0.7511472 -0.6604292 0.002519547 -0.7508841 -0.6601304 -1.75108e-5 -0.7511511 -0.6601313 2.7626e-5 -0.7511503 -0.6607193 -0.005136787 -0.7506157 -0.6601074 7.05391e-5 -0.7511713 -0.6601313 -6.90653e-6 -0.7511503 -0.6600455 -9.32949e-7 -0.7512258 -0.6601567 2.19003e-5 -0.751128 -0.6593755 4.68968e-4 -0.7518137 -0.9543821 0.2939237 0.05257266 -0.9524089 0.05361938 -0.3000707 -0.8789697 0.1209205 -0.4612922 -0.9787512 0.07545191 0.1906652 -0.9755105 0.0899384 0.2007249 -0.976489 0.1089838 0.185989 -0.8605124 0.2936736 -0.4162622 -0.8589017 0.2952306 -0.4184814 -0.9681206 0.1217457 0.2189077 -0.8245375 0.4452485 -0.3491302 -0.7888194 0.4784356 -0.3858284 -0.9332876 -0.009680867 -0.3589996 -0.9511273 5.95022e-4 -0.3087987 -0.9414492 0.007576227 0.3370701 0.4960954 0.7480617 -0.4407868 0.6082283 0.5894247 -0.5316362 -0.1835297 -0.9700605 0.1590586 -0.1950896 -0.9654382 0.1728272 0.6758059 0.4352884 -0.5948197 -0.355422 -0.8811979 0.3117138 -0.3604959 -0.8769391 0.3178373 0.6167059 0.5686479 -0.5443469 0.7220746 0.2830645 -0.631255 -0.505941 -0.739144 0.4446232 -0.49913 -0.7489622 0.4358036 0.6990619 0.3529871 -0.6218622 0.7467502 -0.0923804 -0.6586577 0.7479212 0.07310175 -0.6597501 0.7418532 0.1151409 -0.6606031 -0.6224966 -0.5597938 0.5469267 -0.6186096 -0.5696438 0.5411359 -0.7030259 -0.3489696 0.619657 -0.7000752 -0.3647983 0.6138543 -0.7458506 0.1185521 0.6554787 -0.74585 -0.118552 0.6554793 -0.7459518 -0.1267752 0.6538227 -0.7041093 0.3489714 0.6184247 -0.7458944 0.1215973 0.6548707 -0.6225813 0.5597922 0.5468322 -0.7026661 0.3572028 0.6153588 -0.5053862 0.7391487 0.445246 -0.6193305 0.5680173 0.5420204 -0.3602269 0.8769362 0.3181502 -0.4987878 0.748637 0.4367531 -0.1953057 0.965438 0.1725841 -0.3498197 0.8856424 0.3053914 -0.01839292 0.9996599 0.01848995 -0.1809924 0.9710848 0.1556789 0.7152752 -0.3059447 -0.6283146 0.7428227 -0.1156433 -0.6594249 0.1586408 0.9776927 -0.13766 0.559145 -0.6010735 -0.5710234 -0.001369178 0.9999986 -0.001044213 0.3270434 0.9007509 -0.2858151 0.6751961 -0.4369873 -0.5942664 0.1790068 0.9705032 -0.1614938 0.6991811 -0.3530796 -0.6216757 0.5591534 0.6010667 -0.5710222 0.6082471 -0.5894198 -0.5316201 0.616834 -0.5683578 -0.5445045 0.4963483 -0.7477458 -0.4410382 0.4773101 -0.7731937 -0.4175483 0.4772904 0.7731941 -0.4175703 0.3473974 -0.8850497 -0.3098424 0.3472266 0.8851839 -0.3096501 0.3270435 -0.9007514 -0.2858136 0.178929 -0.9705249 -0.1614494 0.1586216 -0.9776926 -0.1376825 -0.001589477 -0.9999984 -8.37e-4 -0.01833146 -0.9996596 0.01856392 -0.9507963 -4.66106e-4 -0.3098165 -0.9360486 0.006587624 -0.3518092 -0.9402791 -0.006061434 0.3403505 -0.7899855 -0.457446 -0.4082475 -0.8183005 -0.4578005 -0.3475675 -0.9331591 -0.3554074 -0.05384993 -0.968756 -0.1202288 0.2169263 -0.9511561 -0.05371773 -0.3040008 -0.8618497 -0.2944756 -0.4129154 -0.976459 -0.1086274 0.1863542 -0.8809134 -0.1174811 -0.4584648 -0.8583135 -0.2933554 -0.4209995 -0.9787762 -0.0755735 0.1904884 -0.9755107 -0.08999156 0.2007002 -0.8660254 0 0.5000002 -0.8660255 0 0.5 0.3203497 -7.97899e-4 0.9472991 0.3200352 0 0.9474057 0.3205334 -1.45845e-5 0.9472373 0.3217216 0.01154363 0.9467639 0.3203826 -8.57801e-5 0.9472882 0.3210386 8.1258e-4 0.9470658 0.3203858 0 0.9472873 0.3206335 1.18293e-5 0.9472035 0.320447 1.87741e-4 0.9472665 0.3204489 -7.67492e-4 0.9472655 0.3212431 -0.01198393 0.9469209 0.3205972 -1.34172e-4 0.9472156 0.320469 -1.48173e-5 0.9472591 0.3198454 2.22854e-4 0.9474697 0.3218075 -0.01565253 0.9466757 0.3196409 0.008519172 0.9475005 0.5344501 0 -0.8452 0.5344521 0 -0.8451988 0.7579371 0.008938789 -0.6522665 0.7421715 0 -0.67021 0.3919458 0 0.9199883 0.3919655 0 0.91998 0.1604105 -0.01150381 0.9869833 0.9514985 0 -0.3076535 0.1300072 0 0.9915131 0.9438451 -0.008939385 -0.3302673 -0.08046907 0.01489865 0.9966458 0.9991884 0 -0.04028046 0.9991886 0 -0.0402792 -0.3166295 0 0.9485493 0.9797908 0 0.2000253 -0.2643294 -0.01448166 0.9643238 0.9797919 0 0.2000197 -0.5344712 0 0.8451867 0.9034537 0 0.4286857 -0.5344626 0 0.8451922 0.9034554 0 0.4286821 0.7746435 0 0.6323984 -0.721192 0 0.6927353 0.6007142 0 0.799464 -0.7211942 0 0.6927329 0.6007274 0 0.799454 -0.8660394 0 0.4999758 -0.8660413 0 0.4999725 -0.9605203 0 0.2782099 -0.9991886 0 0.04027974 -0.9991886 0 0.0402792 -0.9797908 0 -0.2000253 -0.9797905 0 -0.2000266 -0.9034537 0 -0.4286857 -0.9034586 0 -0.4286753 -0.7745766 0 -0.6324802 -0.7745696 0 -0.6324888 -0.6007611 0 -0.7994286 -0.6007702 0 -0.7994219 -0.3410947 0.01448303 -0.9399175 -0.3919591 0 -0.9199827 -0.160418 -0.01489651 -0.9869368 0.04978752 0 -0.9987599 0.08047306 0.01150786 -0.9966904 0.316686 0 -0.9485304 0.9991885 0 -0.04028087 0.9514991 0 -0.3076518 0.9438447 -0.008937299 -0.3302686 -0.6007723 0 -0.7994202 -0.7745718 0 -0.6324862 0.7579402 0.008940815 -0.6522628 0.7421685 0 -0.6702135 -0.9034554 0 -0.4286821 -0.9797903 0 -0.2000277 0.3166702 0 -0.9485357 0.3166874 0 -0.94853 -0.9797919 0 -0.2000197 0.0804727 0.01150768 -0.9966905 -0.9991886 0 0.0402795 0.0497893 0 -0.9987598 -0.9605206 0 0.278209 -0.3919458 0 -0.9199883 -0.960519 0 0.2782146 -0.3410973 0.01448231 -0.9399164 -0.8660448 0 0.4999666 -0.8660369 0 0.4999801 -0.5344607 0 0.8451935 -0.2643287 -0.01448297 0.964324 -0.3166321 0 0.9485484 -0.08046942 0.01489812 0.9966458 0.1603945 -0.01150447 0.9869861 0.3919638 0 0.9199806 0.6007162 0 0.7994624 0.7746445 0 0.632397 0.9797912 0 0.2000232 0.9797918 0 0.2000208 0.8673176 1.16765e-4 -0.4977552 0.8673304 1.51931e-4 -0.497733 0.8674156 1.52687e-5 -0.4975845 0.8674777 1.7625e-4 -0.497476 0.8673036 3.81011e-5 -0.4977797 0.8673565 2.72037e-4 -0.4976873 0.8674074 3.05369e-4 -0.4975988 0.8672669 -1.00436e-4 -0.4978435 0.8674139 3.33265e-6 -0.4975873 0.8673205 -1.9076e-4 -0.4977502 0.8673962 4.32027e-4 -0.4976181 0.8673544 3.56414e-4 -0.497691 0.8666867 -7.65482e-4 -0.4988524 0.8683685 0.003234744 -0.4959092 0.8675535 -6.40181e-7 -0.4973438 0.867378 -7.57883e-6 -0.4976501 0.8673249 0 -0.4977426 0.8672515 -5.13758e-6 -0.4978705 0.8675598 4.68663e-6 -0.4973329 0.8673198 0 -0.4977513 0.8678569 -6.05771e-4 -0.496814 0.8671422 3.64897e-4 -0.4980606 0.8675518 5.03825e-6 -0.4973469 0.8672765 -6.04563e-6 -0.4978269 0.8672007 -7.6825e-5 -0.4979588 0.8672499 -5.02178e-6 -0.497873 0.8673019 -3.32384e-5 -0.4977827 0.8672736 -1.99352e-4 -0.497832 0.8674153 2.57033e-7 -0.497585 0.8673127 -1.4716e-4 -0.4977637 0.8674268 -8.6171e-7 -0.4975648 0.8673245 -1.47703e-4 -0.497743 0.8673458 -1.65638e-4 -0.4977061 0.8674382 4.0356e-7 -0.4975449 0.8673443 -2.15146e-4 -0.4977087 0.8673582 -2.27402e-4 -0.4976845 0.8675329 -7.60432e-5 -0.4973798 0.8674135 -2.21705e-4 -0.4975882 0.8672081 1.26347e-4 -0.4979461 0.8687594 -0.004549264 -0.4952136 0.8674028 4.31992e-4 -0.4976066 0.8674025 -9.21836e-5 -0.4976072 0.8674106 4.87232e-5 -0.4975932 0.8674136 -2.93366e-4 -0.497588 0.8674101 -1.07142e-5 -0.4975942 0.8674054 3.09674e-4 -0.4976021 0.8673238 5.51648e-4 -0.4977442 0.867411 2.60332e-4 -0.4975925 0.8674052 -9.77778e-5 -0.4976026 0.8674306 2.3241e-4 -0.4975584 0.8674989 3.31145e-4 -0.4974392 0.8674277 2.50954e-4 -0.4975634 0.8674119 -2.77306e-5 -0.4975907 0.8674724 1.53758e-4 -0.4974854 0.8674791 1.39503e-4 -0.4974738 0.8675065 1.476e-4 -0.4974259 0.8675144 1.39431e-4 -0.4974123 0.8675153 1.47942e-4 -0.4974106 0.867456 -2.37855e-4 -0.4975141 0.867402 -5.3319e-5 -0.4976083 0.8674169 3.79418e-4 -0.4975823 0.8678959 -4.69839e-4 -0.496746 0.8675699 -2.49469e-6 -0.4973152 0.8673391 7.57435e-6 -0.4977177 0.8674122 -2.3092e-4 -0.4975902 0.8674087 5.52933e-7 -0.4975964 0.8674083 -1.89112e-6 -0.4975972 0.867285 6.82375e-6 -0.4978122 0.8674069 -2.17452e-4 -0.4975996 0.8674148 1.41654e-6 -0.497586 0.867407 2.24602e-4 -0.4975995 0.867408 2.59965e-4 -0.4975976 0.8674145 1.37339e-6 -0.4975863 0.8674319 9.32568e-7 -0.4975559 0.8674108 -1.58196e-5 -0.4975928 0.867406 0 -0.4976011 0.8675462 4.25247e-6 -0.4973568 0.8672632 8.40153e-6 -0.49785 0.8675452 -7.55862e-6 -0.4973584 0.8675057 2.22972e-6 -0.4974274 0.8671675 -2.78057e-6 -0.4980165 0.8665475 -0.002883851 -0.4990863 0.867467 -2.81568e-4 -0.4974948 0.8673336 -2.65386e-4 -0.4977273 0.8674905 1.76178e-4 -0.4974539 0.8675453 -5.1526e-7 -0.4973583 0.8674429 -2.51286e-4 -0.4975368 0.8675217 3.35265e-5 -0.4973994 0.8675135 -9.13531e-5 -0.4974137 0.867495 -1.32041e-4 -0.4974462 0.867456 -1.86962e-4 -0.497514 0.8674393 -2.64027e-4 -0.4975431 0.867522 -1.42098e-4 -0.497399 0.8674804 -2.09009e-4 -0.4974715 0.8675169 -1.5238e-4 -0.4974077 0.8674072 2.21938e-5 -0.4975992 0.867408 -3.5373e-4 -0.4975975 0.8674067 1.32529e-5 -0.4976 0.8674132 -3.95539e-4 -0.4975886 -0.8851888 0.006015539 0.4651932 0.04609495 0.2448197 0.9684724 -0.8431568 -0.006947517 0.5376231 -0.8849459 -0.007265865 0.4656373 -0.8316996 0.006326735 0.5551898 -0.8652835 3.88714e-4 0.5012826 -0.2502269 -0.7786067 -0.5754635 -0.3719055 -0.8001688 -0.4705489 0.004822134 -0.9386064 -0.3449562 0.1700663 -0.8555198 -0.4890435 0.1676981 -0.8557182 -0.4895138 -0.7133068 -0.1574799 -0.6829302 -0.6593708 -0.4487237 -0.6032223 -0.6560029 -0.45244 -0.6041177 -0.3679487 -0.7943505 -0.4833438 -0.4304473 -0.8052733 -0.4077376 0.006038248 -0.9414058 -0.337222 -0.1306111 -0.9650565 -0.2271713 -0.728163 -0.1137664 -0.6758965 -0.7250339 -0.09070461 -0.6827142 -0.5272604 -0.7731388 -0.3524954 -0.5162059 -0.7800501 -0.3536291 -0.7488204 -0.4062573 -0.5236632 -0.7487596 -0.4063543 -0.5236747 0.1848707 -0.9618082 0.201861 -0.2199394 -0.9635881 -0.1520683 -0.1297065 -0.9642634 -0.2310247 -0.2245647 -0.9648931 -0.1362061 -0.5886768 -0.7636637 -0.2650989 -0.7635771 -0.09740126 -0.6383284 0.01520371 -0.9270582 0.3746092 -0.3118489 -0.9474813 -0.07091921 -0.2984626 -0.9518194 -0.07042813 -0.4107337 -0.9116184 0.01580047 -0.815445 -0.3448943 -0.464863 -0.8154422 -0.3449024 -0.4648619 -0.6768426 -0.7082104 -0.2008036 -0.6891241 -0.6954859 -0.2034882 -0.4088388 -0.9125881 0.005835175 -0.7616958 -0.03167891 -0.64716 -0.8746712 -0.2405372 -0.4208235 -0.8706706 -0.2618883 -0.4163499 -0.5204644 -0.8462074 0.1142367 -0.4984264 -0.8585664 0.1201457 -0.7938768 -0.6001874 -0.09764635 -0.7938789 -0.6001839 -0.09765172 -0.7718535 -0.02954202 -0.6351138 -0.9105404 -0.1761707 -0.3740056 -0.6469314 -0.7262269 0.2325389 -0.6508839 -0.7233717 0.2303987 -0.890022 -0.4557261 -0.01321774 -0.8900178 -0.4557344 -0.0132156 -0.9212815 -0.08699804 -0.3790405 -0.9208782 -0.08395588 -0.3807031 -0.7660678 -0.5491904 0.3339613 -0.7656035 -0.5496232 0.3343135 -0.9531814 -0.2995786 0.04120647 -0.9531781 -0.2995901 0.04119861 -0.7587124 0.04177856 -0.6500847 -0.784035 0.02356415 -0.6202693 -0.8467698 -0.3492794 0.401229 -0.835264 -0.3628594 0.4131189 -0.9347396 -0.009022414 -0.3552192 -0.9855386 -0.1547697 0.06899261 -0.9967675 -0.01542437 0.07884579 -0.9855431 -0.1547449 0.06898474 -0.6361178 -0.1490796 0.7570531 -0.889496 -0.1753037 0.4219781 -0.8827541 -0.1866497 0.4311694 -0.7738244 0.07206976 -0.6292867 -0.9247735 0.07040232 -0.3739488 -0.9287755 0.06109291 -0.3655734 -0.8962981 -0.01857876 0.4430629 -0.9967663 -0.01540261 0.07886517 -0.733642 0.0949614 -0.6728684 -0.8255094 -0.01909637 0.5640655 -0.6863677 0.1359084 0.7144427 -0.8963046 -0.01857942 0.4430498 -0.9895821 0.1243601 0.0725395 -0.9895836 0.1243386 0.07255595 -0.9573057 0.2854067 0.04592257 -0.8982601 0.1784754 -0.4015912 -0.9093397 0.1639983 -0.3823691 -0.7387155 0.1185145 -0.6635162 -0.8875787 0.1504222 0.4354046 -0.8874263 0.1499902 0.4358643 -0.8745308 0.2700719 -0.4028117 -0.9573047 0.2854091 0.04592722 -0.8458449 0.3443972 0.407354 -0.6850939 0.1281098 -0.7171013 -0.7062287 0.1479323 -0.6923562 -0.823513 0.3221088 -0.4669821 -0.8258838 0.3214952 -0.463203 -0.8474687 0.3425251 0.4055531 -0.7859113 0.379858 -0.4879052 -0.8900197 0.4557304 -0.01321905 -0.8900224 0.4557252 -0.01321625 -0.6794341 0.1476658 -0.718724 -0.8127186 0.5766811 -0.08323258 -0.8127297 0.5766662 -0.08322572 -0.7423118 0.4105312 -0.5295633 -0.737255 0.4095319 -0.5373442 -0.7650107 0.5516453 0.3323345 -0.7643148 0.5500065 0.3366239 -0.6319029 0.1332104 -0.7635141 -0.6469163 0.1594262 -0.7457095 -0.7424499 0.6539637 -0.145257 -0.7424711 0.653943 -0.1452419 -0.5583306 -8.62187e-4 -0.8296182 -0.6652522 0.4489661 -0.5965477 -0.6654282 0.4491304 -0.5962275 -0.4360496 0.7315931 0.5240537 -0.6743483 0.6955999 0.2477807 -0.6743698 0.6954686 0.2480905 -0.6582556 0.7203727 -0.2185466 -0.6582614 0.7203733 -0.2185276 -0.6290616 0.1338071 -0.7657527 -0.6286543 0.1328056 -0.7662613 -0.2923151 0.8892468 0.3518409 -0.4976156 0.812691 0.3031702 -0.5895924 0.788929 0.1731237 -0.5895909 0.7889349 0.1731021 -0.3479663 -0.04330182 -0.9365065 -0.5429193 -0.01778757 -0.8395965 -0.5499379 -0.06141012 -0.8329449 -0.568206 -0.07484656 -0.8194755 -0.556057 -0.0492928 -0.8296813 -0.5753152 0.4593845 -0.676741 -0.5758411 0.4599665 -0.6758979 -0.5385454 0.7786147 -0.3220685 -0.535405 0.7753342 -0.3349605 -0.255974 -0.128081 -0.9581611 -0.1257118 -0.06781816 -0.9897461 0.09553778 -0.0881229 -0.9915175 -0.4869704 0.8691797 0.08594375 -0.4867442 0.8695668 0.08326894 -0.6043106 0.1248545 -0.7869055 -0.6038257 0.1200087 -0.7880307 -0.566852 -0.07971328 -0.819954 -0.5836152 -0.1001693 -0.8058284 -0.4304721 0.804032 -0.4101544 -0.3861172 0.7929433 -0.4713327 0.1941816 -0.1520618 -0.9691082 0.3106823 -0.1039857 -0.9448087 0.520819 -0.1152016 -0.8458583 -0.2621929 -0.1634119 -0.9510792 -0.2621862 -0.1634094 -0.9510814 -0.5030115 0.447442 -0.7394425 -0.5030227 0.4474479 -0.7394313 -0.5831345 -0.1057426 -0.8054642 -0.6037853 -0.1204361 -0.7879965 -0.3623469 0.7991936 -0.4795772 0.5505926 -0.1390254 -0.8231159 -0.3397749 0.9398221 -0.03588306 -0.3397549 0.9398373 -0.03567463 -0.5837786 0.1003828 -0.8056834 -0.3009967 -0.2618058 -0.9169835 -0.5833274 0.1054851 -0.8053584 0.2324265 0.9337385 0.2722323 -0.300996 -0.2618006 -0.9169852 -0.2185907 0.9637067 -0.1532564 -0.130898 0.964322 -0.2301064 -0.2187511 0.9637627 -0.1526747 -0.4249925 0.4080543 -0.8080056 -0.4249948 0.4080424 -0.8080105 0.1688408 -0.2843589 -0.9437335 0.1688474 -0.2843621 -0.9437313 -0.6257042 -0.1319726 -0.7688156 -0.604245 -0.1249814 -0.7869356 -0.2502328 0.7786104 -0.575456 -0.2502285 0.7786058 -0.575464 -0.1246564 0.9650453 -0.2305391 -0.566906 0.07967883 -0.8199201 -0.5682079 0.07499665 -0.8194604 -0.3563113 0.3449272 -0.8683706 -0.3563151 0.3449387 -0.8683646 -0.114466 0.7100818 -0.6947528 -0.1144658 0.7100681 -0.6947668 0.005004823 0.9386717 -0.344776 0.006327986 0.9417365 -0.3362922 -0.3563116 -0.3449287 -0.8683699 -0.3563141 -0.3449384 -0.8683651 0.5103099 -0.3428163 -0.7887083 0.5109159 -0.3424869 -0.7884591 0.1013262 -0.4555754 -0.8844118 0.1013132 -0.4555804 -0.8844107 -0.3479599 0.04330152 -0.9365089 -0.556032 0.04931294 -0.8296967 -0.5402758 0.01815611 -0.8412922 -0.5478515 0.06533968 -0.8340201 -0.3009974 0.2618049 -0.9169836 -0.3009998 0.2618088 -0.9169816 0.1686599 0.8560113 -0.4886702 0.1684501 0.8555784 -0.4894999 0.00506103 0.6002429 -0.7998018 0.00505799 0.6002339 -0.7998086 0.3126962 0.7228118 -0.6162502 -0.6278804 -0.1380493 -0.7659691 0.3132327 0.7237431 -0.6148831 0.1013185 0.4555756 -0.8844125 0.1013222 0.4555842 -0.8844076 -0.2621885 0.1634145 -0.9510799 0.1688482 0.2843593 -0.943732 -0.1257118 0.06781816 -0.9897461 0.09553778 0.0881229 -0.9915175 -0.2559722 0.1280801 -0.9581616 -0.2621933 0.163405 -0.9510802 0.4280557 0.5478876 -0.7187403 0.4290013 0.5492613 -0.7171261 0.1941807 0.1520622 -0.9691084 0.5097949 0.3427715 -0.7890608 0.310684 0.1039863 -0.9448081 0.5213131 0.1152223 -0.845551 0.1688395 0.2843632 -0.9437325 -0.4250043 -0.408046 -0.8080036 0.5115297 0.3417867 -0.788365 -0.4249817 -0.4080504 -0.8080134 0.5504245 0.1384438 -0.8233264 -0.650761 -0.1345522 -0.7472656 -0.6302621 -0.1619144 -0.7593111 0.4306862 -0.5479475 -0.7171214 0.4278868 -0.5490732 -0.7179356 0.005069792 -0.6002349 -0.7998077 0.005052387 -0.6002457 -0.7997998 -0.5030282 -0.447428 -0.7394396 -0.5030058 -0.4474573 -0.7394371 -0.6761819 -0.148998 -0.7215107 -0.6788339 -0.1407439 -0.7206773 -0.114457 -0.7100733 -0.694763 -0.2502313 -0.7786107 -0.5754562 -0.1144773 -0.7100708 -0.6947622 0.3149268 -0.7227964 -0.6151313 0.312116 -0.7234603 -0.6157831 -0.5736683 -0.4591444 -0.6783002 -0.5762646 -0.4577774 -0.6770222 0.5024363 -0.08919668 0.860001 0.4763017 -0.1631093 0.864021 0.4811324 -0.3083176 0.8206412 0.4232054 -0.4705367 0.7742691 0.4554658 -0.3396254 0.8229251 -0.3599349 -0.3172726 0.8773739 0.03598743 -0.1341672 0.9903051 -0.2115949 -0.02699893 0.9769845 -0.6688782 -0.07295298 0.7397837 -0.6792547 -0.08926063 0.7284542 0.02652871 -0.2371174 0.9711188 -0.1457991 -0.2685937 0.9521555 -0.6948235 -0.04938435 0.7174828 -0.7326012 -0.08730113 0.6750363 0.06815147 -0.454282 0.8882474 -0.1670905 -0.3364865 0.9267458 -0.8349019 9.75783e-5 0.5503987 -0.8381543 1.3883e-5 0.5454332 -0.6684237 0.07886403 0.7395879 -0.700999 0.02969288 0.7125439 -0.3633109 0.2210065 0.9050754 -0.6769793 0.0923919 0.73018 0.02477532 0.4217045 0.9063949 -0.3068318 0.3866426 0.8696906 -0.4060482 0.2734 0.8719963 -0.7683603 0.08663809 0.6341264 0.05005985 0.1325771 0.9899078 0.05565774 0.2579804 0.9645457 0.04227262 0.2606362 0.9645112 -0.2358409 0.01969093 0.9715922 0.4313784 0.5149782 0.7407497 0.4671971 0.3050286 0.8298702 0.4859428 0.0909143 0.8692492 0.4797419 0.2802941 0.8314343 0.4949331 -2.01685e-4 0.8689312 0.4998388 0.001144766 0.8661177 0 -1 -2.12558e-5 0 -1 -1.93349e-5 0 -1 -1.16861e-5 0 -1 9.66594e-6 0 -1 1.78374e-5 0 -1 1.93323e-5 0 -1 -1.16895e-5 0 -1 3.27856e-5 0 -1 -2.69644e-5 0 -1 -2.12567e-5 0 -1 -1.0627e-5 0 -1 8.91965e-6 0 -1 2.98492e-5 0 -1 -2.013e-5 0 -1 -1.78395e-5 0 -1 1.93334e-5 0 1 -5.31327e-6 0 1 -3.97368e-6 0 1 1.00652e-5 0 1 9.66632e-6 0 1 -1.78396e-5 0 1 -6.64272e-6 0 1 -7.16497e-6 0 1 -8.9187e-6 0 1 1.00646e-5 0 1 -9.40486e-6 0 1 7.95748e-6 0 1 -5.26915e-6 0 1 7.46224e-6 0 1 1.27773e-5 0 1 -1.58914e-5 0 1 4.45967e-6 0 1 -1.93349e-5 0 1 8.92061e-6 0 1 2.12553e-5 0 1 2.51631e-6 0 1 -5.8429e-6 0.2572211 0.04701799 -0.9652081 0.2693828 0.07405155 -0.960182 0.274883 0.2748638 -0.9213519 0.3423185 0.4076187 -0.8465608 0.3514649 0.5112563 -0.7842764 0.4800629 0.6396565 -0.6003159 0.4599667 0.6355511 -0.6200851 0.9354948 -0.2472918 0.2523813 0.9076526 -0.4018879 0.1210488 0.5790179 0.7225499 -0.3777035 0.8557143 -0.509577 0.08991289 0.6893702 0.692831 -0.2115516 0.7137846 0.6733509 -0.19264 0.7595463 -0.6462932 -0.07344728 0.7010979 -0.6727778 -0.2362878 0.8648886 0.4964378 0.07428008 0.8345915 0.547925 0.05688095 0.6245181 -0.7154921 -0.3131268 0.9663169 0.09179228 0.2404281 0.9287541 0.2923836 0.2278766 0.9639456 0.05076813 0.2612118 0.5069747 -0.6921322 -0.513741 0.4706378 -0.6176422 -0.6300938 0.364461 -0.5527691 -0.7494095 0.327599 -0.3542913 -0.8758748 0.2645472 -0.2713742 -0.9254031 0.2707148 0.09986054 -0.9574662 0.2748868 0.2748566 -0.9213529 0.3423254 0.4076095 -0.8465624 0.3514723 0.5112501 -0.7842771 0.9541651 -0.09503024 0.2837931 0.4800589 0.6396758 -0.6002987 0.4599551 0.6355446 -0.6201003 0.9493197 -0.2361347 0.207443 0.8980956 -0.4017625 0.1789172 0.8468828 -0.5307539 0.03301441 0.5866009 0.7280571 -0.3547285 0.7033621 0.6744748 -0.2244226 0.7721555 -0.6342539 -0.03870409 0.7516217 0.6538719 -0.08669781 0.6984446 -0.6791277 -0.2257452 0.8515421 0.5200638 0.06640744 0.8548942 0.5142793 0.0683574 0.6224956 -0.7178158 -0.311833 0.9529751 0.2028341 0.2251595 0.935313 0.2657511 0.2335936 0.5202445 -0.6842022 -0.5110901 0.5190945 -0.6806312 -0.5169934 0.372236 -0.547931 -0.7491409 0.3725474 -0.5201172 -0.7685614 0.2719794 -0.2693346 -0.9238432 0.2797231 -0.2368297 -0.9304121 0.2510492 0.04731369 -0.9668173 0.2510486 0.04730117 -0.9668182 0.2706927 0.09979766 -0.957479 0.2748729 0.2747973 -0.9213747 0.3423312 0.407651 -0.84654 0.3527004 0.5318803 -0.7698739 0.4853346 0.635067 -0.6009494 0.9395341 -0.2620711 0.2204415 0.9404667 -0.2434067 0.2372249 0.504691 0.698904 -0.5067744 0.8339563 -0.5517063 0.01171594 0.8564095 -0.5086638 0.08845412 0.6893715 0.6928287 -0.2115548 0.6858423 0.6955183 -0.2141839 0.7595436 -0.6462917 -0.07348853 0.8648572 0.4965003 0.07422631 0.8345932 0.5479264 0.05684059 0.6153828 -0.7108619 -0.3405575 0.6161634 -0.7125275 -0.3356298 0.9634452 0.1204673 0.2392926 0.9287475 0.2923852 0.2279012 0.9617294 0.05123132 0.2691689 0.4407504 -0.5931582 -0.6737228 0.458254 -0.6505711 -0.6056077 0.3579429 -0.5229591 -0.7735573 0.2797185 -0.2671144 -0.9221755 0.2811799 -0.262223 -0.9231344 0.2851547 0.2656384 -0.9209359 0.2888975 0.2707762 -0.9182693 0.3840179 0.5404867 -0.7486016 0.3605778 0.5272382 -0.7694177 0.9551245 -0.1217615 0.2700212 0.9493152 -0.2361213 0.2074785 0.5350863 0.691554 -0.4852172 0.5103319 0.6936304 -0.5083682 0.8981122 -0.4017071 0.1789579 0.8353224 -0.5496847 0.009136915 0.7037634 0.6842439 -0.1911218 0.6813863 0.7010954 -0.2101855 0.7727262 -0.6335057 -0.03955584 0.8544635 0.5160152 0.06016975 0.8273303 0.5604482 0.03771477 0.9042832 0.3890438 0.1758321 0.6153775 -0.7108574 -0.3405765 0.6161736 -0.7125297 -0.3356062 0.9550271 0.2011711 0.2178385 0.9561148 0.1251507 0.2649186 0.4477028 -0.6151477 -0.6489651 0.4582529 -0.6505617 -0.6056186 0.3597417 -0.5218958 -0.7734408 0.333794 -0.3827726 -0.861433 0.2633333 -0.2716469 -0.9256693 0.2783895 -0.06881117 -0.9580002 0.2460103 0.04753679 -0.9681009 -0.3798999 -0.9201729 -0.09464633 -0.6597443 3.18774e-4 -0.7514902 -0.6599738 2.00347e-4 -0.7512887 -0.660299 9.85295e-5 -0.7510029 -0.6548679 0.001024007 -0.7557427 -0.6608849 -4.7816e-4 -0.7504873 -0.6615347 0.002313375 -0.749911 -0.6604791 2.75664e-5 -0.7508445 -0.660206 2.55352e-4 -0.7510845 -0.6592764 -0.001598596 -0.7518991 -0.6599419 -4.52225e-4 -0.7513166 -0.6597263 -8.38099e-4 -0.7515056 -0.6620758 1.40705e-5 -0.7494369 -0.6619715 1.97771e-4 -0.749529 -0.6621178 2.95853e-5 -0.7493997 -0.6620235 -9.52831e-5 -0.7494832 -0.6626012 0.00117886 -0.7489716 -0.2325263 4.46718e-4 0.97259 -0.2037279 -3.3997e-4 0.9790275 -0.7740283 1.27318e-5 0.6331511 -0.7624484 -3.03785e-4 0.6470491 -0.7015154 0 0.7126544 -0.6840092 -0.0275231 0.7289541 -0.3686886 0.06031644 -0.927594 -0.8929556 0.02747839 0.4493053 -0.4389876 -0.0274989 -0.8980723 -0.8823062 0 0.470676 -0.126959 -0.06052416 -0.9900597 0.1043864 0.09533274 -0.9899572 -0.9966305 -0.0456497 0.06814593 -0.9977271 -0.03221529 0.0591852 -0.9647082 0.06386953 -0.2554582 0.297223 -0.09533172 -0.9500371 0.5096661 0.06052881 -0.8582404 -0.9225887 -0.0638653 -0.3804624 -0.7585074 0.0322234 -0.6508672 -0.7521993 0.0456745 -0.6573509 0.7595332 0.0275045 -0.6498869 0.7067047 -0.06031185 -0.7049334 0.9665332 0.03230464 -0.2544997 0.9545716 -0.03225415 -0.2962311 0.9850138 0 0.1724761 0.9884787 -0.02748465 0.1488439 0.8770094 0.02750688 0.4796854 0.8885562 0 0.4587678 0.6154971 -0.03225344 0.787479 0.6222701 -0.04564374 0.7814708 0.3377879 0.06385529 0.9390538 0.1783509 -0.09533601 0.9793375 -0.05250394 0.06053924 0.996784 -0.3704353 0.02749323 0.9284514 -0.2980893 -0.0603044 0.9526312 0.7544853 -0.1183909 -0.6455507 0.4938248 -0.2541354 -0.8315962 0.6849163 0.2532627 -0.6831895 -0.627676 -0.1707716 -0.759513 -0.5503328 0.1708225 -0.8172843 -0.8497503 -0.2600837 -0.4585641 0.09685534 -0.3832902 -0.9185357 -0.7795686 0.2556742 -0.571755 0.2757778 0.3833012 -0.8814913 -0.9662062 0.1943694 -0.1693105 -0.3272984 -0.2557075 -0.9096645 -0.1609234 0.3696427 -0.9151328 -0.9540057 -0.1942138 -0.2283728 -0.8931286 -0.3834214 0.2351795 -0.9595205 0.2673121 0.08868348 -0.7138478 -0.2532615 0.6529012 -0.8533031 0.2543367 0.4551775 -0.6794866 0.1185045 0.7240543 -0.3679609 -0.1183348 0.9222807 -0.0508607 -0.2541705 0.9658212 -0.2889035 0.253261 0.9232517 0.1654872 0.3832968 0.9086791 0.3261703 -0.2671791 0.906768 0.61104 0.194099 0.7674345 0.6098937 0.1385313 0.7802813 0.8711609 -0.1183986 0.4765086 0.9850116 0 0.1724888 0.8885726 0 0.4587362 0.9819115 0.1182802 0.1478502 0.9577137 -0.1385225 -0.2521826 0.9458678 0.1385252 -0.2935049 0.8665685 -3.20928e-5 -0.4990584 0.8664543 -1.4127e-4 -0.4992566 0.8674749 -0.001235425 -0.4974796 0.867574 -3.38204e-4 -0.497308 0.8676766 -3.45338e-4 -0.4971292 0.8676537 3.61941e-4 -0.4971691 0.8666841 6.31555e-4 -0.4988569 0.8672174 0.002135872 -0.4979253 0.8674883 -0.001283347 -0.4974559 0.8672157 0.001599669 -0.49793 0.8683207 -3.55604e-4 -0.4960032 0.8670685 0.001319587 -0.4981874 0.8663673 0.001405954 -0.4994055 0.8674462 -0.00137639 -0.4975292 0.8680424 5.33127e-4 -0.49649 0.8673372 -4.92002e-4 -0.497721 0.8679269 1.28727e-4 -0.496692 0.8669332 -6.35542e-4 -0.498424 0.8669432 -5.86252e-4 -0.4984067 0.8673158 5.78318e-4 -0.4977581 0.8678199 0.001502335 -0.4968767 0.8674808 3.19759e-4 -0.4974707 0.8667871 1.09388e-4 -0.4986786 0.8675904 -3.37847e-4 -0.4972797 0.8674674 4.08117e-4 -0.4974941 0.8675681 -3.3477e-4 -0.4973183 0.867446 -0.001441359 -0.4975292 0.8666771 -1.15446e-4 -0.4988696 0.8676161 -4.60616e-5 -0.4972348 0.8675793 -9.34245e-5 -0.4972989 0.8675021 -0.001467049 -0.4974315 0.8674014 3.06331e-4 -0.497609 0.8674738 -0.001512825 -0.4974808 0.8675889 0 -0.4972823 0.8673315 5.22307e-4 -0.4977308 0.8671842 1.41373e-4 -0.4979876 0.8666709 4.82103e-5 -0.4988804 0.8672457 3.88583e-4 -0.4978803 0.8676813 2.14951e-4 -0.4971207 0.8672643 3.7119e-4 -0.497848 0.8673379 -4.91988e-4 -0.4977196 0.867577 2.57048e-4 -0.4973028 0.8672167 -5.0291e-4 -0.4979309 0.8675952 3.37757e-4 -0.4972711 0.867226 -2.18131e-4 -0.4979149 0.8674348 3.84209e-4 -0.4975509 0.8668287 -5.25137e-4 -0.498606 0.8671643 -1.34269e-4 -0.4980224 0.8673548 -8.82168e-4 -0.4976897 0.8676737 -2.90567e-4 -0.4971343 0.8675799 -2.23379e-4 -0.4972977 0.8677229 -1.70795e-4 -0.4970484 0.867162 0.001430213 -0.4980241 0.8671883 2.22922e-4 -0.4979804 0.8675853 -0.001296341 -0.4972867 0.8676456 -6.772e-5 -0.4971833 0.8671963 2.04893e-4 -0.4979665 0.8670669 0.001218497 -0.4981902 0.8673003 9.31079e-4 -0.4977844 0.8674527 -0.001563131 -0.4975172 0.8676805 6.81037e-4 -0.4971218 0.8681948 6.60742e-4 -0.4962232 0.8673126 -3.84132e-4 -0.4977636 0.8669427 -4.30085e-4 -0.4984076 0.8678871 0.001107275 -0.4967603 0.8669186 -7.25132e-4 -0.4984492 0.8678598 7.11396e-4 -0.4968087 0.8664584 -7.8896e-4 -0.4992488 0.867425 4.79088e-4 -0.4975676 0.867607 -4.07896e-4 -0.4972504 0.8675501 -3.18471e-4 -0.4973497 0.8676916 -3.42223e-4 -0.4971027 0.8674327 -4.39973e-4 -0.4975545 0.8671795 0.0014171 -0.4979936 0.8667124 2.59337e-4 -0.4988083 0.8674423 -4.59525e-4 -0.4975376 0.8676205 -7.11782e-5 -0.4972271 0.8672483 2.4925e-4 -0.497876 0.8677126 6.14174e-5 -0.4970663 0.866829 -5.23031e-5 -0.4986054 0.8671423 0.00123769 -0.4980589 0.8672199 0.001183569 -0.4979242 0.8673438 -5.49409e-4 -0.4977094 0.867619 2.46053e-4 -0.4972296 0.86732 -2.69523e-4 -0.4977511 0.8676253 2.51113e-4 -0.4972186 0.8672209 -3.42028e-4 -0.4979234 0.8674889 3.42932e-4 -0.4974564 0.8675988 4.40333e-4 -0.4972647 0.8671495 2.19792e-4 -0.498048 0 -1 -2.78715e-5 0 -1 3.58835e-5 0 -1 -5.77243e-6 0 -1 -4.67762e-6 0 -1 3.68805e-6 0 -1 -9.44822e-6 0 -1 -2.934e-6 0 -1 -2.33881e-6 0 1 -2.78792e-5 0 1 9.02353e-6 0 1 -4.92985e-6 0 1 5.01047e-6 0 1 -6.29263e-6 0 1 1.85706e-5 0 1 -7.29185e-6 -0.07592803 -0.9849992 -0.1549566 -0.4933854 0.0989198 -0.8641676 -0.3170316 -0.7628156 -0.5635633 -0.494249 0.1880943 -0.8487275 -0.2544792 -0.870615 -0.4210346 -0.4084438 0.5499759 -0.7284917 -0.4626686 -0.3749159 -0.803353 -0.4645746 -0.368789 -0.8050872 -0.2174067 0.8923582 -0.395514 -0.3426681 0.738406 -0.5808058 -0.09545803 0.984995 -0.1437802 0.1159079 0.9777934 0.1746007 0.216261 0.8923591 0.3961396 0.4018651 0.6063431 0.6861869 0.4159194 0.5500431 0.7241987 0.4943267 0.1444976 0.8571823 0.493413 0.09897243 0.8641459 0.4645947 -0.3686478 0.8051401 0.4487873 -0.4175589 0.7900853 0.2485203 -0.8706486 0.42451 0.2679643 -0.8527181 0.448405 0.06135529 -0.9902282 0.1252354 -0.1013866 -0.9759129 -0.1931701 -0.4899508 0.09890443 -0.8661213 -0.3165566 -0.7627915 -0.5638628 -0.2316932 -0.8923384 -0.3873635 -0.4103592 0.5500053 -0.7273923 -0.4665093 0.3748551 -0.8011572 -0.4560873 -0.3749181 -0.8071066 -0.4207741 -0.5499561 -0.7214552 -0.2174083 0.8923579 -0.3955138 -0.3269174 0.7628553 -0.5578322 -0.5003571 -0.09887528 -0.8601549 -0.09545904 0.984992 -0.1438003 0.1159118 0.977791 0.1746115 0.2162522 0.8923675 0.3961256 0.3947237 0.623064 0.6752663 0.4138046 0.5500197 0.7254269 0.494315 0.1420896 0.8575916 0.4934024 0.09897112 0.8641521 0.4645979 -0.3686584 0.8051335 0.4627116 -0.3747746 0.803394 0.2750575 -0.8402436 0.4672623 0.3170123 -0.7628058 0.5635873 0.1306574 -0.965815 0.2238976 0.08016586 -0.9850382 0.1525558 0.2349735 -0.8706313 0.4321904 0.09544509 -0.9849957 0.1437834 -0.4968975 0.09893453 -0.8621513 -0.4907855 0.1421085 -0.8596132 -0.09543722 -0.9849953 -0.1437916 -0.3858501 0.6230487 -0.6803898 -0.234975 -0.8706295 -0.4321935 -0.4072102 0.5805177 -0.7051092 -0.3264465 -0.7628642 -0.5580959 -0.4604765 -0.3687514 -0.8074553 -0.4599337 -0.3748797 -0.8049387 -0.1003167 0.9778674 -0.1836083 -0.1376444 0.9631195 -0.2312029 0.2265844 0.8923912 0.3902531 0.1972799 0.9150952 0.3516839 0.401512 0.5858144 0.7039955 0.4334239 0.5103722 0.7427409 0.4854375 0.1420854 0.8626484 0.5016003 -0.1511497 0.8517928 0.4549705 -0.3687247 0.8105825 0.343084 -0.7384059 0.5805602 -0.1003006 -0.9778812 -0.1835439 -0.07870095 -0.9846282 -0.1559278 -0.4549523 0.3687416 -0.810585 -0.4955838 0.188106 -0.8479462 -0.2827674 -0.8335217 -0.4746412 -0.3794194 -0.6230344 -0.6840096 -0.48731 -0.1420868 -0.8615918 -0.4696403 -0.3687779 -0.8021477 -0.2349732 0.8706187 -0.4322162 -0.3430925 0.7384076 -0.5805531 -0.09544587 0.9849976 -0.1437706 0.0954535 0.9849925 0.1438 0.3430865 0.7384 0.5805663 0.234976 0.8706281 0.4321959 0.4549633 0.3686981 0.8105987 0.5015992 0.1511606 0.8517915 0.4854353 -0.1420996 0.8626474 0.4334238 -0.5103722 0.7427409 0.4015103 -0.5858256 0.7039871 0.2265903 -0.8923856 0.3902625 0.1972845 -0.9150943 0.3516837 0.867407 6.20313e-5 -0.4975996 0.8674148 -5.21032e-5 -0.497586 0.8674222 0 -0.4975728 0.8674238 9.62554e-5 -0.4975699 0.8674048 2.45118e-4 -0.4976033 0.8672951 -0.001182377 -0.4977931 0.8674015 1.18239e-4 -0.4976089 0.8673869 0 -0.4976343 0.8674741 1.79817e-5 -0.4974822 0.8673863 -3.83003e-5 -0.4976354 0.8674932 -8.60267e-5 -0.4974493 0.8673694 -2.1003e-4 -0.4976649 0.8674668 0 -0.4974952 0.8673862 -7.69054e-5 -0.4976356 0.8672005 6.67505e-4 -0.4979588 0.867498 -1.16279e-4 -0.4974407 0.867275 7.81399e-5 -0.4978294 0.8675582 -1.33944e-4 -0.4973357 0.867371 -2.02137e-4 -0.497662 0.8674419 0 -0.4975386 0.8674852 2.70935e-5 -0.497463 0.8674135 -2.96572e-5 -0.4975883 0.8674328 -2.8519e-5 -0.4975545 0.8677148 5.23775e-4 -0.4970623 0.8674138 -3.05649e-5 -0.4975875 0.8675305 0 -0.4973841 0.8673658 1.41881e-4 -0.4976712 0.8673971 0 -0.4976168 0.8674229 -1.62123e-5 -0.4975717 0.8674117 1.48247e-4 -0.497591 0.8673996 -1.93353e-5 -0.4976125 0.8670818 -1.28479e-4 -0.498166 0.8673662 -1.63546e-4 -0.4976704 0.8672999 0 -0.4977861 0.867344 -1.1316e-4 -0.4977092 0.8673539 3.89939e-4 -0.4976919 0.8673517 1.9459e-4 -0.4976959 0.8673831 3.87073e-5 -0.4976409 0.8674068 -1.92272e-4 -0.4975997 0.8674144 0 -0.4975866 0.8674211 3.03153e-4 -0.4975748 0.8674367 1.14801e-4 -0.4975478 0.8674879 2.17278e-4 -0.4974585 0.8674649 7.48427e-5 -0.4974985 0.8674118 0 -0.497591 0.8675266 0 -0.4973908 0.8674682 3.78177e-4 -0.4974924 0.8675959 2.09609e-4 -0.4972701 0.8671448 8.90658e-5 -0.4980561 0.8674079 0 -0.4975978 0.867429 4.05841e-4 -0.4975609 0.8675179 -5.30835e-5 -0.4974061 0.867389 0 -0.4976307 0.8674817 -2.10036e-4 -0.4974691 0.8674315 1.87079e-4 -0.4975566 0.8674104 -2.11158e-4 -0.4975937 0.8673027 0 -0.4977811 0.8674125 0 -0.49759 0.8673904 4.19232e-4 -0.497628 0.8673837 -8.02969e-5 -0.4976401 0.867503 -2.22465e-4 -0.4974321 0.8674851 0 -0.4974633 0.867365 1.79693e-4 -0.4976726 0.8667235 0.001033008 -0.4987878 0.8673738 2.34431e-4 -0.4976571 0.8674467 2.83593e-4 -0.4975303 0.8672765 0 -0.4978269 0.8674737 0 -0.4974833 0.8675953 4.18304e-5 -0.497271 0.8674045 -1.91662e-4 -0.4976037 0.8674191 -8.66823e-5 -0.4975782 0.8674164 -9.58273e-5 -0.497583 0.8672056 -5.10391e-5 -0.4979503 0.8683979 5.71803e-4 -0.4958679 0.8674341 -2.87125e-5 -0.4975522 0.8674504 1.41382e-4 -0.4975239 0.8675021 0 -0.4974337 0.8674019 0 -0.4976083 0.8674245 1.53133e-4 -0.4975689 0.8676626 -6.07953e-4 -0.4971534 0.8673521 -2.08748e-4 -0.4976949 0.8674743 2.59917e-4 -0.4974819 0.8676537 1.8594e-4 -0.4971692 0.8674284 6.4185e-5 -0.4975622 0.002927422 -0.9998701 0.01585 0.1581884 -0.9522771 0.2610457 0.5058069 0.1091347 0.8557155 0.3098656 0.7808774 0.542415 0.3105608 -0.7686715 0.5591924 0.3502026 0.7083947 0.6128093 0.4225503 -0.5506404 0.7198933 0.4854245 -0.1391122 0.8631401 0.3403632 0.7320411 0.590143 0.1284367 0.9654958 0.2265436 0.1097459 0.9758872 0.1886797 -0.1097484 0.9758854 -0.1886878 -0.1284534 0.9654935 -0.2265436 -0.3369086 0.7383546 -0.5842303 -0.3388466 0.7340018 -0.5885782 -0.4727747 0.2899627 -0.8321092 -0.4921699 0.1880083 -0.849954 -0.461314 -0.3687942 -0.8069574 -0.4690768 -0.3403795 -0.8149288 -0.318669 -0.7628313 -0.5626177 -0.2652792 -0.8516243 -0.4520656 -0.1051977 -0.9758973 -0.191201 -0.006798148 -0.9998782 -0.01404899 -0.006588995 -0.9998834 -0.01378279 0.4748055 -0.3918123 0.7880628 0.4718585 0.2991533 0.8293714 0.244124 -0.8751606 0.417729 0.3202491 -0.759285 0.5665041 0.4635201 0.3696123 0.8053173 0.322852 0.7586554 0.5658698 0.417537 -0.5550522 0.7194303 0.4694831 -0.3048501 0.8286446 0.3208981 0.7627377 0.5614765 0.4966721 -0.1307106 0.8580394 0.02953553 0.9976456 0.06189614 0.1116861 0.9758883 0.1875325 -0.2249727 0.8953365 -0.3843955 -0.1262075 0.9654882 -0.2278249 -0.4066205 0.5858741 -0.7010073 -0.3345773 0.7340078 -0.5910083 -0.4717364 0.2899424 -0.8327053 -0.4956116 0.1420139 -0.8568556 -0.4613173 -0.3687764 -0.8069638 -0.4690877 -0.3404192 -0.8149059 -0.300251 -0.7921314 -0.531392 -0.2642366 -0.8516494 -0.4526284 0.004621088 -0.9998617 0.01598221 0.09477823 -0.9832978 0.1553796 0.2373708 -0.875137 0.4216518 0.409394 0.5505748 0.7275054 0.4657726 0.3696342 0.8040066 0.340188 -0.7384127 0.5822532 0.4109269 -0.5500601 0.7270302 0.3263561 0.7627899 0.5582503 0.4936746 -0.06212455 0.867425 0.1482765 0.9522795 0.2667919 0.4929763 -0.1821377 0.8507646 0.1097359 0.9759047 0.1885951 -0.1097514 0.9758936 -0.1886435 -0.1284542 0.9654843 -0.2265825 -0.3369003 0.7383896 -0.5841909 -0.3388327 0.7340368 -0.5885426 -0.4658923 0.3341909 -0.8193051 -0.4982227 0.15112 -0.8537781 -0.4879376 -0.1420478 -0.8612429 -0.4314736 -0.5104413 -0.7438282 -0.4021561 -0.5858032 -0.7036371 -0.2395113 -0.8777958 -0.41486 -0.2020465 -0.9111849 -0.3590534 0.1074381 -0.9759026 0.1899245 0.1306978 -0.9655049 0.2252075 0.4831278 0.211791 0.8495483 0.3342407 -0.7384037 0.5856988 0.356766 -0.7015551 0.616878 0.4651298 0.3747667 0.8020002 0.3481521 0.7083394 0.6140404 0.4833566 -0.2209964 0.8470697 0.3228839 0.7628233 0.5602201 0.4957545 -0.1356599 0.8578019 0.1284498 0.9654908 0.2265574 0.1097329 0.9758955 0.1886441 -0.1097443 0.9758934 -0.1886483 -0.1284537 0.9654856 -0.2265772 -0.3368942 0.7383792 -0.5842075 -0.3388215 0.734053 -0.5885289 -0.4659045 0.3341832 -0.8193013 -0.4982161 0.1511178 -0.8537824 -0.4879237 -0.1420407 -0.861252 -0.4224091 -0.5424057 -0.7262002 -0.3870493 -0.6229909 -0.6797612 -0.1540299 -0.952293 -0.2634632 -0.1251533 -0.9671561 -0.2212374 0.8674138 -1.27621e-5 -0.4975875 0.8674557 0 -0.4975144 0.8674656 0 -0.4974972 0.8673936 -5.8899e-6 -0.4976228 0.8673672 0 -0.497669 0.8674073 0 -0.497599 0.8674211 -5.88794e-6 -0.4975748 0.8674019 1.73898e-5 -0.4976084 0.8674288 7.69195e-6 -0.4975615 0.8673957 -1.27626e-5 -0.4976192 0.8674207 1.32873e-5 -0.4975757 0.8674477 -1.34467e-5 -0.4975285 0.8673992 -6.32291e-6 -0.4976131 0.8674142 4.73376e-6 -0.4975868 0.8674112 -6.15893e-6 -0.4975922 0.8672865 -4.68196e-5 -0.4978095 0.8674081 -7.43077e-6 -0.4975975 0.8674639 0 -0.4975002 0.867449 1.04782e-5 -0.4975263 0.8674061 2.57005e-5 -0.497601 0.8673946 9.28042e-6 -0.4976209 0.8674197 -9.12977e-6 -0.4975772 0.8673557 -1.04792e-5 -0.4976888 0.8674396 0 -0.4975427 0.8674022 4.87455e-6 -0.4976077 0.8673917 0 -0.4976262 0.8673889 2.1898e-5 -0.497631 0.8674375 3.26442e-5 -0.4975463 0.8674085 -8.37142e-6 -0.4975969 0.867377 6.95309e-6 -0.4976517 0.8674338 0 -0.4975526 0.8673647 9.35898e-6 -0.4976732 0.8674265 0 -0.4975653 0.867439 0 -0.4975435 0.8674095 -1.33035e-5 -0.4975949 0.8673904 2.35592e-5 -0.4976283 0.8673922 -3.54985e-6 -0.4976254 0.8674583 0 -0.49751 0.8673971 0 -0.4976165 0.4704737 -0.2140855 0.8560503 -0.4747782 -0.3559274 -0.8049232 -0.4423951 -0.4009003 -0.8022254 -0.3207573 -0.7850047 -0.5299833 -0.3252167 -0.7816138 -0.5322725 -0.1063494 -0.9636882 -0.2449384 -0.06505763 -0.9975231 -0.02674251 0.1436457 -0.9701887 0.1951924 0.1929696 -0.8988477 0.3934915 0.3504092 -0.7489295 0.5624215 0.3719614 -0.6053265 0.703722 0.4939218 -0.3446832 0.7982699 0.01312261 0.999691 -0.02111202 0.003016114 0.999978 -0.005914807 0.8674191 0 -0.4975783 0.867406 8.78553e-5 -0.4976012 0.8673754 1.32619e-4 -0.4976544 0.8674231 -1.17402e-4 -0.4975712 0.8674301 -1.18269e-4 -0.4975592 -0.8674287 0 0.4975617 -0.8674226 -4.64305e-5 0.4975721 -0.8674042 6.3472e-5 0.4976045 -0.8674074 0 0.4975989 -0.8674089 -7.50296e-5 0.497596 0.4937989 -0.3448033 0.798294 0.4703853 -0.2141827 0.8560745 -0.4748207 -0.3558085 -0.8049508 -0.4425157 -0.4006841 -0.8022669 -0.3207076 -0.7850816 -0.5298995 -0.325151 -0.7816808 -0.5322143 -0.1062852 -0.9637327 -0.2447914 -0.0650168 -0.9975263 -0.02672636 0.1436699 -0.9701768 0.1952334 0.1929196 -0.8989004 0.3933959 0.3505288 -0.7487807 0.5625451 0.3719567 -0.6054371 0.7036293 0.01318532 0.9996885 -0.02119517 0.003040909 0.999978 -0.005914807 0.8673928 0 -0.497624 0.8674331 -7.5447e-5 -0.4975541 0.8674076 0 -0.4975985 0.8674541 -1.76612e-4 -0.4975172 0.8674457 -1.17448e-4 -0.4975319 -0.8673285 -1.39666e-4 0.4977362 -0.8674167 -7.65306e-5 0.4975827 -0.8674139 -3.92558e-5 0.4975873 -0.8674024 0 0.4976076 -0.8674173 2.80036e-5 0.4975813 0.4899498 -0.3049203 0.8166841 0.4452513 -0.0863102 0.8912363 -0.8673089 5.56743e-5 0.4977704 -0.8673877 -1.0095e-4 0.497633 -0.8674167 -1.30716e-5 0.4975826 -0.867403 1.64091e-5 0.4976063 -0.8674151 0 0.4975855 -0.8673335 -1.82198e-5 0.4977275 -0.004621386 -0.9999893 4.66092e-4 -0.01061606 -0.9998893 0.01043391 0.8671945 8.21778e-5 -0.4979698 0.8674331 4.28833e-5 -0.4975538 0.8674309 5.83252e-5 -0.4975578 0.8674269 3.80067e-5 -0.4975647 0.8673547 -2.23315e-4 -0.4976905 0.8675003 8.9388e-5 -0.4974367 0.8679567 3.5781e-4 -0.4966397 0.8673632 -8.37439e-5 -0.4976758 -0.474375 0.4294828 -0.7684485 -0.4600161 0.347306 -0.8171681 -0.5030417 -0.1124629 -0.8569139 0.5181133 0.1782734 0.8365268 -0.4821714 -0.1506087 -0.8630341 0.4071523 0.5408059 0.7360408 0.3950187 0.5545874 0.7323886 0.2208788 0.8831188 0.4139008 0.2663747 0.8545302 0.4458957 0.0472815 0.9970238 0.06089371 -0.006942689 0.9998201 0.01765841 -0.1700623 0.931805 -0.3206528 -0.266471 0.8775202 -0.3986876 -0.32299 0.7090062 -0.6268873 0.4899082 -0.3050689 0.8166535 0.4452185 -0.08624893 0.8912585 -0.8672738 8.35054e-5 0.4978317 -0.8673581 4.71322e-5 0.4976845 -0.8674132 -1.74557e-5 0.4975886 -0.867396 -5.04454e-5 0.4976186 -0.8674146 -1.30736e-5 0.4975863 -0.8673545 -3.64542e-5 0.4976908 -0.004621863 -0.9999892 4.73567e-4 -0.01061636 -0.9998893 0.01042711 0.8674172 2.68615e-5 -0.4975818 0.867409 2.7945e-4 -0.497596 0.8678869 -1.368e-4 -0.496762 0.8673889 0 -0.497631 0.8673851 -7.28947e-5 -0.4976376 0.8673813 -1.32958e-4 -0.4976444 0.8673704 5.57561e-4 -0.4976628 0.8673878 -9.8075e-5 -0.4976327 -0.4743631 0.4292393 -0.7685917 -0.4600371 0.3475158 -0.8170672 -0.5030082 -0.1127167 -0.8569001 0.5182151 0.1783255 0.8364527 -0.4821841 -0.1507505 -0.8630021 0.407098 0.5409467 0.7359674 0.3949549 0.5547112 0.7323293 0.2208889 0.8831167 0.4138998 0.2663756 0.8545303 0.4458948 0.04730892 0.9970226 0.06089258 -0.006958842 0.9998194 0.01768732 -0.1699877 0.9318364 -0.3206015 -0.2664895 0.8775053 -0.3987079 -0.322794 0.7092635 -0.6266973 0.4938872 -0.3447345 0.7982692 0.4704555 -0.2141394 0.8560467 -0.474781 -0.3559872 -0.8048951 -0.4424242 -0.4009199 -0.8021996 -0.3207747 -0.7850286 -0.5299376 -0.3251348 -0.7816689 -0.5322417 -0.1063246 -0.9637132 -0.2448509 -0.06505239 -0.9975222 -0.02679085 0.1436598 -0.9701835 0.1952072 0.1929509 -0.8988773 0.3934334 0.3504364 -0.7488936 0.5624525 0.3719278 -0.6053956 0.7036803 0.01312971 0.9996906 -0.02112597 0.00302267 0.999978 -0.005928516 0.8674213 8.18716e-5 -0.4975746 0.8672748 -1.50757e-4 -0.4978297 0.8674204 -1.18301e-4 -0.4975761 0.8674351 -2.84017e-4 -0.4975504 0.867361 2.63619e-4 -0.4976795 -0.8674411 0 0.49754 -0.867409 4.64349e-5 0.497596 -0.8674264 -6.34913e-5 0.4975656 -0.8674132 -2.8e-5 0.4975886 -0.867388 -3.77237e-5 0.4976325 0.4899573 -0.3049968 0.8166511 0.4452816 -0.08633345 0.8912187 -0.8672968 8.35197e-5 0.4977915 -0.8673901 0 0.4976289 -0.8674038 0 0.4976051 -0.8673893 1.04105e-5 0.4976301 -0.8674082 -4.62451e-5 0.4975975 -0.8674052 -6.53841e-6 0.4976025 -0.00468409 -0.9999889 5.84888e-4 -0.01061433 -0.9998892 0.01044386 0.8673117 -4.29349e-5 -0.4977657 0.8674213 1.22082e-4 -0.4975746 0.8673359 -1.89934e-4 -0.4977234 0.8673744 -6.19037e-4 -0.4976561 0.8674731 1.7869e-4 -0.4974842 0.8673694 -2.97923e-5 -0.497665 0.8673794 -2.78927e-5 -0.4976477 0.8669334 -3.57646e-4 -0.4984241 -0.4744351 0.4291018 -0.7686243 -0.4599956 0.3468509 -0.817373 -0.5030598 -0.1133973 -0.85678 0.5181308 0.1778372 0.836609 -0.4819408 -0.1520478 -0.8629105 0.4071828 0.5407322 0.7360781 0.3952789 0.5541557 0.7325749 0.2209055 0.883098 0.4139309 0.2663996 0.8545197 0.4459006 0.04727512 0.9970248 0.06088358 -0.006972014 0.9998198 0.01765739 -0.1700038 0.9318237 -0.3206295 -0.2665399 0.8774526 -0.3987901 -0.3228408 0.7091583 -0.6267922 0.4934573 -0.3459392 0.7980137 0.4704911 -0.2141605 0.856022 -0.4726334 -0.357202 -0.8056206 -0.4428516 -0.3978458 -0.8034933 -0.3207898 -0.7849857 -0.5299919 -0.3252415 -0.7816095 -0.5322636 -0.1062988 -0.9637168 -0.2448479 -0.06504893 -0.9975224 -0.02679175 0.1436484 -0.9701868 0.1951987 0.1929447 -0.8988754 0.3934407 0.3504595 -0.7489006 0.5624288 0.3719867 -0.6053024 0.7037294 -0.002080321 0.9999741 -0.006891846 0.008214771 0.9999385 -0.00745815 0.8674312 -1.33212e-4 -0.4975574 0.8674072 4.43256e-5 -0.497599 0.8674462 -2.75914e-4 -0.4975311 0.8674086 0 -0.4975966 0.8674146 9.46791e-5 -0.4975861 -0.8673764 1.39584e-4 0.4976527 -0.8673672 -8.66954e-5 0.4976689 -0.8673486 0 0.4977012 -0.8674226 -1.46059e-5 0.4975721 -0.8674368 0 0.4975476 0.4899426 -0.3049355 0.8166827 0.4452601 -0.08628475 0.8912342 -0.8673878 -1.3921e-5 0.4976329 -0.8674071 -3.14215e-5 0.4975993 -0.8674367 -1.04117e-5 0.4975477 -0.8674122 0 0.4975903 -0.8674041 2.61668e-5 0.4976047 -0.8672997 -3.64412e-5 0.4977863 -0.004617393 -0.9999892 4.58709e-4 -0.01062875 -0.999889 0.01044839 0.8675803 -1.23049e-4 -0.4972973 0.8675862 -1.16182e-4 -0.4972868 0.8673931 1.28718e-4 -0.4976238 0.8674141 -2.34692e-5 -0.4975871 0.8674407 -5.57513e-4 -0.4975406 0.8674157 -1.38787e-5 -0.4975844 0.867379 -8.37158e-5 -0.4976483 0.8676347 1.34101e-4 -0.4972025 -0.4742904 0.429603 -0.7684335 -0.4600108 0.3478801 -0.8169268 -0.5030416 -0.1124 -0.8569221 0.518143 0.1779534 0.8365767 -0.4822352 -0.1503917 -0.8630362 0.4071467 0.5408134 0.7360383 0.3951838 0.5543934 0.7324464 0.220888 0.8831271 0.4138782 0.2663922 0.8545169 0.4459105 0.04731744 0.9970163 0.06099081 -0.00696516 0.9998199 0.01765692 -0.1699482 0.9318576 -0.3205606 -0.266455 0.8775241 -0.3986893 -0.3228175 0.7093701 -0.6265645 0.8674074 0 -0.4975987 0.8674073 0 -0.497599 0.8674086 0 -0.4975967 0.8674085 0 -0.4975968 0.867407 0 -0.4975994 0.8674057 0 -0.4976019 0.4975975 0 0.8674082 0.4975983 0 0.8674077 0.3518539 -0.7071083 0.6133488 0.351855 -0.7071064 0.6133504 0 -1 -1.63851e-6 -0.3518495 -0.7071066 -0.6133533 -0.3518489 -0.7071054 -0.613355 -0.4975901 0 -0.8674123 -0.4975966 0 -0.8674086 -0.3518497 0.7071062 -0.6133536 -0.3518494 0.7071063 -0.6133537 0.351853 0.7071092 0.6133482 0.3518542 0.7071061 0.6133511 -0.8674073 0 0.4975989 -0.8674063 0 0.4976006 -0.8674076 0 0.4975985 -0.8674072 0 0.4975991 -0.8674086 0 0.4975966 -0.8674086 0 0.4975968 0.4817957 -0.3049669 0.8215037 0.46863 -0.2330888 0.8520889 -0.867228 -1.44634e-5 0.4979112 -0.8674445 0 0.4975342 -0.867417 0 0.497582 -0.8674134 0 0.4975884 -0.86741 3.095e-5 0.4975942 -0.8673692 -5.42207e-5 0.4976651 -0.8674327 1.33352e-4 0.4975546 -0.0138964 -0.9999035 -1.53321e-4 -0.002523839 -0.9999968 -2.92289e-4 0.8674166 -5.58282e-5 -0.4975827 0.8675593 1.79026e-4 -0.4973338 0.867425 -1.72809e-4 -0.4975679 0.8674169 6.11506e-5 -0.4975821 0.8673825 8.57966e-5 -0.4976419 0.8673678 0 -0.4976676 0.8673897 1.19257e-4 -0.4976297 0.8674167 0 -0.4975824 -0.474332 0.4295476 -0.7684388 -0.459984 0.3476423 -0.8170433 0.487118 0.1389705 0.8622084 -0.5030698 -0.1111621 -0.8570671 0.4990783 0.1782752 0.8480206 -0.481563 -0.1509779 -0.8633092 0.3990004 0.5697814 0.7184344 0.4111908 0.554355 0.7236108 0.2208883 0.8831002 0.4139355 0.2663635 0.8545324 0.4458978 0.04730445 0.9970204 0.0609315 -0.006958425 0.9998199 0.01765888 -0.1700033 0.9318255 -0.3206247 -0.2664613 0.877532 -0.3986679 -0.3228646 0.7092074 -0.6267244 0.4934768 -0.3458381 0.7980456 0.4705095 -0.2141323 0.8560189 -0.4726158 -0.3572549 -0.8056075 -0.4429511 -0.3977563 -0.8034826 -0.3207619 -0.7850079 -0.529976 -0.3252176 -0.7816011 -0.5322905 -0.1062991 -0.9637219 -0.2448279 -0.06503075 -0.9975235 -0.02679288 0.1436527 -0.9701878 0.1951909 0.1929282 -0.8988787 0.3934412 0.3504937 -0.7488364 0.5624929 0.3719589 -0.6053864 0.7036717 -0.002064347 0.9999741 -0.006899774 0.00819087 0.9999387 -0.007458388 0.8674214 -4.43056e-5 -0.4975745 0.8674034 0 -0.4976056 0.8674069 -1.18321e-4 -0.4975998 0.8673973 9.46624e-5 -0.4976164 0.867418 -4.4409e-5 -0.4975802 -0.8674033 0 0.497606 -0.8673234 8.17651e-5 0.4977451 -0.8674266 0 0.4975652 -0.86741 -7.55677e-5 0.4975944 -0.8674114 2.0174e-5 0.4975917 -0.09518492 -0.9825571 -0.1597549 0.01077675 -0.9998702 0.01198869 -0.4931626 0.1745966 -0.8522365 -0.4956 0.1048375 -0.8622005 -0.257036 -0.8587561 -0.4432501 -0.2208414 -0.8953329 -0.3867921 -0.4186273 0.5424821 -0.7283298 -0.4165783 0.5500335 -0.7238271 -0.4194196 -0.5500442 -0.7221764 -0.3147234 0.7801174 -0.540709 -0.3945204 -0.6121674 -0.6852771 -0.4734967 -0.3083745 -0.8250492 -0.4958391 -0.151017 -0.8551827 -0.1289442 0.9670451 -0.219539 -0.2543262 0.858745 -0.4448317 -0.09212046 0.9825618 -0.1615118 0.09211409 0.9825648 0.1614975 0.1320151 0.9655193 0.2243763 0.2516757 0.8615807 0.440838 0.4041499 0.5809512 0.7065116 0.3423935 0.7339097 0.5866373 0.4636868 0.3832197 0.798835 0.4909495 0.1746014 0.8535122 0.5002725 0.06613266 0.863339 0.4923998 -0.1510134 0.8571684 0.4146234 -0.5500491 0.7249369 0.4664794 -0.3748583 0.801173 0.2548477 -0.8587256 0.4445707 0.3447754 -0.7277554 0.5928762 0.1030896 -0.9778429 0.1821975 0.2116245 -0.9071571 0.363705 -0.8660358 0 0.4999819 -0.8660156 -3.334e-5 0.5000171 -0.8660157 0 0.5000171 -0.8660201 -7.84421e-5 0.5000094 -0.866023 0 0.5000044 -0.8660242 -6.40823e-5 0.5000022 -0.8660244 0 0.500002 -0.8660222 3.67433e-5 0.5000057 -0.8660214 4.05367e-5 0.500007 -0.8660245 -3.84513e-5 0.5000016 -0.8660166 2.35149e-5 0.5000154 -0.866018 -1.76785e-5 0.5000128 -0.86606 3.08742e-4 0.4999402 -0.8660221 -3.38968e-5 0.500006 0.8659539 0 -0.500124 0.8660775 0 -0.4999099 0.866011 1.57858e-5 -0.5000252 0.8659068 -4.34266e-5 -0.5002055 0.8660803 1.3807e-4 -0.499905 0.8660014 -1.60999e-4 -0.5000416 0.8660132 0 -0.5000213 0.8660227 1.8876e-5 -0.5000047 0.8660331 1.62098e-5 -0.4999867 0.8660197 1.2428e-5 -0.5000101 0.8660115 -1.26203e-4 -0.5000243 0.8660233 1.83079e-5 -0.5000039 0.8660905 -1.60968e-4 -0.4998874 -0.1196571 -0.9709422 -0.2072521 -0.4963546 0.1205421 -0.8597103 -0.2323621 -0.8854551 -0.402464 -0.1196572 -0.9709422 -0.2072524 -0.4675086 0.3546022 -0.8097488 -0.3315606 -0.7485123 -0.5742795 -0.4963548 0.1205412 -0.8597104 -0.232362 -0.8854562 -0.4024615 -0.4114919 0.5680652 -0.7127247 -0.4114899 -0.5680674 -0.712724 -0.4675095 0.3545994 -0.8097494 -0.3315598 -0.7485108 -0.5742819 -0.3315608 0.7485108 -0.5742813 -0.4675087 -0.3546004 -0.8097495 -0.4114894 0.5680704 -0.712722 -0.4114922 -0.5680667 -0.7127233 -0.4963545 -0.1205439 -0.8597101 -0.4675099 -0.3545996 -0.8097493 -0.2323614 0.8854562 -0.4024618 -0.3315621 0.7485097 -0.5742821 -0.4963548 -0.1205393 -0.8597105 -0.1196573 0.9709421 -0.2072525 -0.2323626 0.8854553 -0.4024633 -0.1196575 0.9709421 -0.2072525 0.1196573 0.9709421 0.2072526 0.2323634 0.8854544 0.4024646 0.1196575 0.970942 0.2072529 0.33156 0.7485127 0.5742794 0.2323642 0.8854538 0.4024654 0.4114918 0.5680644 0.7127254 0.3315614 0.7485103 0.5742818 0.4114929 0.5680602 0.712728 0.4675067 0.3546102 0.8097463 0.4675073 0.3546096 0.8097463 0.4963557 0.1205362 0.8597105 0.4963556 0.1205374 0.8597103 0.4963542 -0.1205382 0.8597111 0.467507 -0.3546105 0.8097461 0.4963558 -0.1205356 0.8597105 0.4114928 -0.5680606 0.7127279 0.4675056 -0.3546099 0.8097472 0.3315607 -0.7485108 0.5742813 0.4114925 -0.5680631 0.7127261 0.2323634 -0.8854542 0.402465 0.3315598 -0.7485134 0.5742785 0.1196569 -0.9709423 0.2072519 0.2323638 -0.8854539 0.4024655 0 -1 2.35793e-7 0.1196575 -0.970942 0.2072528 -0.8660424 3.33424e-5 0.4999707 -0.8660316 0 0.4999894 -0.8660233 0 0.5000038 -0.86599 0 0.5000614 -0.8660376 0 0.4999789 -0.866035 -3.57274e-6 0.4999835 -0.8660111 7.15417e-6 0.5000249 -0.8660033 3.26973e-5 0.5000382 -0.8660258 -1.63804e-6 0.4999993 -0.8660313 -1.2519e-6 0.4999898 -0.8660205 0 0.5000086 -0.8660274 0 0.4999967 -0.8660244 0 0.5000019 -0.8660278 0 0.4999959 -0.8660488 0 0.4999595 -0.8660261 0 0.499999 -0.866024 -3.26967e-5 0.5000025 -0.8660242 0 0.5000021 -0.8660244 4.89267e-7 0.5000017 -0.866024 -7.16764e-7 0.5000026 -0.8660262 -9.21665e-7 0.4999987 -0.8660205 0 0.5000085 -0.8660233 0 0.5000039 -0.8660334 1.11141e-5 0.4999863 0.9484673 0.1660087 -0.2699094 0.948475 0.1660088 -0.2698825 0.8989967 0.05020385 -0.4350684 0.8944959 0.03644436 -0.4455884 0.9839856 0.1742314 -0.03762578 0.9839857 0.1742332 -0.03761613 0.9720465 0.08214342 0.2199503 0.9720433 0.08213925 0.2199659 0.8923354 -0.1004517 0.4400534 0.8923381 -0.1004407 0.4400505 0.7368208 -0.3329685 0.5884108 0.7367999 -0.3329839 0.5884282 0.5097351 -0.5641787 0.6495173 0.5097421 -0.5641751 0.6495147 0.9648455 0.1036268 -0.2415259 0.9146649 0.04137665 -0.4020899 0.9648407 0.1036272 -0.2415446 0.9981589 0.05922549 -0.0130794 0.9981597 0.05922228 -0.01304167 0.9720471 -0.08214133 0.2199486 0.9720433 -0.08214086 0.2199651 0.8683009 -0.2954955 0.3984171 0.8683016 -0.295504 0.3984092 0.6842086 -0.5334171 0.4973176 0.6842109 -0.5334178 0.4973138 0.4303535 -0.7433952 0.5120151 0.4303448 -0.7434025 0.5120118 0.9230585 0.01562756 -0.3843425 0.9732698 0.03523111 -0.2269468 0.9732694 0.03522098 -0.2269499 0.9981586 -0.05924052 -0.01304173 0.9981598 -0.05921268 -0.01307666 0.9523848 -0.2416598 0.1859136 0.9523946 -0.2416428 0.1858854 0.8216201 -0.4733929 0.3175528 0.8216165 -0.4733962 0.3175568 0.6091523 -0.7028635 0.3673097 0.6091553 -0.7028585 0.3673143 0.3318326 -0.8794085 0.3413618 0.3318307 -0.8794062 0.3413694 0.9024046 -0.008302569 -0.4308097 0.9732697 -0.03522843 -0.2269474 0.9003793 -0.00892204 -0.4350145 0.9732696 -0.03522884 -0.226948 0.9839845 -0.1742383 -0.03762561 0.9839866 -0.1742283 -0.03761708 0.9142257 -0.3871005 0.1197695 0.914211 -0.3871283 0.119792 0.755014 -0.6237605 0.20218 0.7550243 -0.6237493 0.2021763 0.5159987 -0.8314581 0.205968 0.5160162 -0.8314486 0.2059631 0.2198914 -0.9643099 0.1474931 0.2199 -0.9643082 0.1474918 0.9648414 -0.1036166 -0.2415467 0.9648444 -0.1036368 -0.2415258 0.9145423 -0.04125672 -0.4023808 0.9564648 -0.2791087 -0.08528429 0.9564633 -0.2791111 -0.08529281 0.8597359 -0.510105 0.02544152 0.8597415 -0.5100961 0.02543008 0.6723608 -0.7378686 0.05899846 0.6723289 -0.7378966 0.05901193 0.4101877 -0.9117196 0.02266311 0.4101822 -0.911722 0.02266597 0.1010524 -0.9931689 -0.05834376 0.1010524 -0.993169 -0.05834269 0.898998 -0.0501877 -0.4350677 0.8963696 -0.0481007 -0.4406901 0.9484726 -0.1660128 -0.2698878 0.9484692 -0.1660094 -0.2699022 0.9171903 -0.3677687 -0.1533238 0.9171835 -0.3677908 -0.1533119 0.7921513 -0.6034025 -0.09166091 0.7921357 -0.6034244 -0.09165179 0.5784062 -0.8091362 -0.1036587 0.5784236 -0.8091229 -0.1036648 0.2978177 -0.9390098 -0.1719456 0.2978205 -0.9390082 -0.1719496 -0.01778519 -0.9643098 -0.2641785 -0.01778459 -0.964309 -0.2641819 0.9251151 -0.218725 -0.3103569 0.925112 -0.2187449 -0.3103523 0.8987357 -0.08714675 -0.4297438 0.8684487 -0.4350636 -0.237732 0.8684455 -0.4350715 -0.2377295 0.7153412 -0.6616675 -0.2246847 0.7153463 -0.6616615 -0.224686 0.478716 -0.8333314 -0.2763873 0.4787005 -0.8333422 -0.2763814 0.185455 -0.9117239 -0.3665596 0.1854615 -0.911723 -0.3665588 -0.1297158 -0.8794061 -0.4580599 -0.1297211 -0.879409 -0.4580527 0.8961222 -0.2587654 -0.3605628 0.8961253 -0.2587491 -0.3605667 0.878212 -0.06533145 -0.4737886 0.88317 -0.07826548 -0.4624774 0.8130679 -0.4770779 -0.3336428 -0.3918928 -0.1197147 -0.9121888 0.813079 -0.4770548 -0.3336484 0.6337882 -0.6814801 -0.36592 0.6337894 -0.6814793 -0.3659194 0.3789848 -0.8091297 -0.4490876 0.3789995 -0.8091194 -0.4490939 0.07962548 -0.8314498 -0.5498647 0.07962954 -0.8314506 -0.5498628 -0.2282384 -0.7433961 -0.6287046 -0.2282393 -0.7433971 -0.6287032 0.8631936 -0.2837439 -0.4175959 0.8631876 -0.2837595 -0.4175976 0.8740784 -0.1132898 -0.4723903 0.7542785 -0.4913407 -0.4354862 0.7542855 -0.4913282 -0.4354883 0.5522444 -0.6616765 -0.5071592 -0.3919021 0.1197179 -0.9121844 0.5522564 -0.6616613 -0.5071659 -0.3918986 0.1197128 -0.9121866 0.2850712 -0.7378885 -0.6117638 -0.1682542 0.1131864 -0.9792239 0.2850655 -0.7378833 -0.6117727 -0.1682609 0.1131858 -0.9792228 -0.01352077 -0.7028604 -0.7111994 -0.3632597 0.3521783 -0.8625618 -0.0135169 -0.702853 -0.7112067 -0.3632619 0.3521757 -0.862562 -0.3076202 -0.5641866 -0.7662005 0.06507581 0.1004486 -0.9928118 -0.3076209 -0.5641918 -0.7661966 0.06507122 0.1004477 -0.9928122 -0.1411781 0.3329777 -0.9323061 0.828219 -0.2922292 -0.4781793 0.8587121 -0.129629 -0.4957922 0.828203 -0.2922782 -0.4781771 -0.1411594 0.3329796 -0.9323083 0.6954726 -0.477086 -0.5373145 0.6954978 -0.4770548 -0.5373097 0.4754503 -0.6034135 -0.6401869 -0.3076222 0.5641913 -0.7661963 -0.3076246 0.5641916 -0.7661951 0.4754487 -0.6034091 -0.6401922 0.2024003 -0.6237643 -0.7549518 0.2955445 0.08214211 -0.9517911 0.2955355 0.08214271 -0.9517938 0.08911627 0.2955099 -0.9511742 0.08910292 0.2955044 -0.9511771 0.2023984 -0.6237708 -0.754947 -0.08858007 -0.5334163 -0.841202 -0.08856093 -0.5334137 -0.8412056 -0.3632497 -0.352181 -0.8625649 -0.3632665 -0.3521724 -0.8625613 -0.08856582 0.5334163 -0.8412033 -0.3919081 -0.119716 -0.9121822 -0.08858031 0.5334134 -0.8412038 0.7932491 -0.2837584 -0.5387365 0.8545208 -0.07656037 -0.5137437 -0.2282353 0.7433986 -0.6287028 0.7932646 -0.2837216 -0.5387331 0.8547989 -0.07183879 -0.5139632 -0.2282411 0.7433969 -0.6287027 0.640104 -0.435077 -0.6332258 0.5104038 0.05921638 -0.8578937 0.6400973 -0.435071 -0.6332367 0.510387 0.05922746 -0.8579028 0.4078301 -0.5101028 -0.7572779 0.4078453 -0.5100849 -0.7572818 0.3152042 0.2416505 -0.9177426 0.3151971 0.2416506 -0.9177451 0.1357891 -0.4733969 -0.87032 0.1357869 -0.4733893 -0.8703244 0.1357933 0.4733932 -0.8703213 0.1357888 0.4733892 -0.8703241 -0.168261 -0.1131859 -0.9792228 -0.1682604 -0.1131862 -0.9792228 -0.141176 -0.3329817 -0.932305 -0.1411601 -0.3329752 -0.9323097 0.7603206 -0.2587458 -0.595788 -0.01351678 0.7028596 -0.7112002 0.7603219 -0.2587586 -0.5957807 -0.01352137 0.7028526 -0.711207 -0.1297168 0.8794079 -0.4580562 0.8331039 -0.103029 -0.5434362 0.5913653 -0.3677652 -0.71766 0.591374 -0.3677836 -0.7176435 -0.129716 0.8794069 -0.4580583 0.8197336 0.0166853 -0.5725021 0.6935617 0.0287466 -0.7198235 0.6831767 0.03521358 -0.7294036 0.3533797 -0.3871259 -0.8516199 0.3533633 -0.3871217 -0.8516286 0.5245572 0.1742433 -0.8333541 0.08911186 -0.2955097 -0.9511746 0.524563 0.1742343 -0.8333524 0.08911067 -0.2955082 -0.9511752 0.3533718 0.3871186 -0.8516264 0.06507575 -0.1004486 -0.9928118 0.06507122 -0.1004478 -0.9928122 0.3533627 0.3871288 -0.8516257 0.7313346 -0.2187336 -0.6459919 0.731324 -0.2187438 -0.6460003 0.8333213 -0.06618136 -0.5488131 0.2024038 0.6237642 -0.754951 0.8377933 -0.05197727 -0.5435079 0.2023973 0.6237673 -0.7549501 0.5521024 -0.2791066 -0.7856733 0.5520892 -0.2791197 -0.785678 0.07962727 0.8314512 -0.5498622 0.07962816 0.8314538 -0.5498582 0.2955377 -0.08214229 -0.9517931 0.3152007 -0.241655 -0.9177426 0.2955352 -0.08214265 -0.9517939 0.3152047 -0.2416503 -0.9177424 -0.01778519 0.9643086 -0.264183 0.7079783 -0.1660132 -0.6864447 0.7079623 -0.1660152 -0.6864607 -0.01778179 0.9643093 -0.2641808 0.8119125 -0.06647533 -0.5799822 0.5104036 -0.05921632 -0.8578938 0.6916124 0.103618 -0.7147976 0.6916043 0.1036313 -0.7148036 0.5245557 -0.1742393 -0.8333559 0.8057303 0.04129093 -0.5908416 0.5103868 -0.05922746 -0.857903 0.5245668 -0.174236 -0.8333495 0.6935607 -0.028746 -0.7198245 0.5521059 0.2791095 -0.7856698 0.6916075 -0.103622 -0.7148018 0.5520904 0.279116 -0.7856784 0.6916074 -0.1036316 -0.7148005 0.8253784 -0.01604056 -0.564352 0.6831766 -0.03521358 -0.7294037 0.8053787 -0.04151099 -0.5913055 0.4078335 0.5101012 -0.7572773 0.4078414 0.5100848 -0.7572838 0.2850658 0.7378908 -0.6117636 0.2850746 0.7378754 -0.6117781 0.1854531 0.9117268 -0.3665536 0.18546 0.9117231 -0.3665592 0.1010535 0.9931688 -0.05834299 0.1010529 0.9931688 -0.05834448 0.7079787 0.1660052 -0.6864463 0.8298388 0.04810523 -0.5559259 0.8262618 0.0502054 -0.5610446 0.7079631 0.1660203 -0.6864588 0.5913767 0.3677535 -0.7176566 0.5913619 0.3677955 -0.7176472 0.4754453 0.6034152 -0.6401891 0.4754492 0.6034148 -0.6401865 0.3789871 0.8091293 -0.4490864 0.3789986 0.8091177 -0.4490978 0.2978184 0.9390093 -0.1719471 0.2978198 0.9390085 -0.1719492 0.2199018 0.9643083 0.1474879 0.2198942 0.9643089 0.1474961 0.7313285 0.2187342 -0.6459985 0.821525 0.08716684 -0.5634704 0.7313299 0.218747 -0.6459926 0.6401064 0.4350582 -0.6332363 0.6400982 0.4350781 -0.6332311 0.5522493 0.6616719 -0.5071599 0.5522493 0.6616709 -0.5071613 0.4787084 0.8333368 -0.276384 0.4787077 0.833337 -0.276385 0.4101843 0.9117211 0.02266514 0.4101822 0.9117219 0.02266842 0.3318414 0.8794047 0.341363 0.3318192 0.8794112 0.3413681 0.7603197 0.258755 -0.5957851 0.7603235 0.2587559 -0.5957798 0.8421026 0.07824647 -0.5336112 0.8448225 0.07349085 -0.5299755 0.6954925 0.4770514 -0.5373196 0.6954792 0.477086 -0.537306 0.6337939 0.6814748 -0.36592 0.6337803 0.6814893 -0.3659166 0.5784127 0.809132 -0.103655 0.5784171 0.8091267 -0.1036708 0.5160056 0.8314557 0.2059603 0.5160104 0.8314496 0.2059732 0.4303473 0.7433972 0.5120174 0.4303498 0.743401 0.5120098 0.7932594 0.2837285 -0.5387371 0.793253 0.2837568 -0.5387317 0.8462137 0.1130068 -0.5207225 0.754283 0.4913293 -0.4354914 0.7542812 0.4913378 -0.435485 0.7153373 0.6616752 -0.2246743 0.7153472 0.6616575 -0.2246951 0.672336 0.7378894 0.05902177 0.6723527 0.7378768 0.05898922 0.609157 0.7028586 0.3673111 0.6091529 0.7028613 0.367313 0.5097528 0.56417 0.6495109 0.5097262 0.5641826 0.6495208 0.8639971 0.08204656 -0.4967669 0.8282078 0.2922589 -0.4781805 0.8282153 0.2922472 -0.4781748 0.8626302 0.08838719 -0.4980531 0.8130722 0.4770642 -0.3336517 0.813077 0.477063 -0.3336415 0.792149 0.6034051 -0.09166407 0.7921438 0.6034141 -0.09165012 0.755014 0.6237596 0.2021832 0.755021 0.6237545 0.2021723 0.684217 0.5334175 0.4973056 0.6842024 0.5334184 0.4973248 0.5653806 0.3521896 0.7458601 0.5653684 0.3521845 0.7458717 0.8740732 0.1129922 -0.4724711 0.8631928 0.283726 -0.4176096 0.8631905 0.2837693 -0.4175851 0.8684463 0.4350697 -0.2377298 0.8684461 0.4350689 -0.2377318 0.8597449 0.5100904 0.02542704 0.8597363 0.5101042 0.02544337 0.8216141 0.4733989 0.3175594 0.8216222 0.4733911 0.3175501 0.7367978 0.3329744 0.5884361 0.7368192 0.332979 0.5884068 0.5940037 0.119713 0.7955051 0.5940179 0.1197182 0.7954938 0.8961266 0.2587494 -0.3605635 0.8829592 0.07185924 -0.4639174 0.8831673 0.07821416 -0.4624913 0.896122 0.2587636 -0.3605647 0.9171868 0.3677842 -0.1533077 0.9171864 0.3677771 -0.1533269 0.9142167 0.3871133 0.1197966 0.9142208 0.3871135 0.119765 0.8683037 0.2954978 0.3984094 0.8683005 0.2955003 0.3984141 0.7639127 0.1131828 0.6353167 0.7639172 0.113188 0.6353104 0.5940216 -0.1197099 0.7954923 0.594007 -0.119719 0.7955018 0.9251113 0.2187402 -0.3103576 0.8987403 0.08715832 -0.4297319 0.9251167 0.2187285 -0.3103497 0.956462 0.2791181 -0.08528506 0.9564643 0.2791075 -0.08529406 0.9523919 0.2416557 0.1858829 0.9523874 0.241648 0.1859157 0.8923346 0.1004479 0.4400561 0.8923397 0.1004444 0.4400463 0.7639209 -0.1131786 0.6353074 0.763908 -0.1131907 0.6353208 0.5653765 -0.3521919 0.7458622 0.5653712 -0.3521826 0.7458705 0.8660774 -8.12065e-5 -0.49991 0.8659949 -9.51058e-5 -0.5000529 0.8660603 3.45917e-6 -0.4999399 0.8659473 6.92312e-6 -0.5001355 0.8467134 -0.001535832 -0.5320472 0.8660232 -3.22206e-5 -0.5000039 0.8660236 2.7373e-5 -0.5000033 0.8660277 3.116e-5 -0.4999961 0.8660373 2.44807e-5 -0.4999796 0.8660307 -8.93569e-5 -0.4999909 -0.4999981 0 -0.8660265 -0.5000001 0 -0.8660255 0.8660252 0 -0.5000005 0 1 5.77327e-6 0 1 1.95459e-6 0 1 7.70787e-7 0 1 6.77454e-6 0 1 -1.50744e-6 0 1 -1.1845e-5 0 1 -1.95455e-6 0 1 -1.50749e-6 0 1 5.92305e-6 0 1 2.18829e-6 0 1 -3.369e-6 0 1 6.13604e-6 0 1 -4.83851e-6 0 1 -1.69362e-6 0 1 -7.38251e-7 -0.8660253 0 0.5000002 -0.8660252 0 0.5000005 0.5000005 0 0.8660252 0.4999981 0 0.8660265 -0.8451813 0 0.5344798 -0.8451817 0 0.5344793 -0.6927291 0 0.721198 -0.6927298 0 0.7211972 -0.5000044 0 0.8660229 0.9199816 0 0.3919616 -0.5000012 0 0.8660248 0.9199812 0 0.3919625 0.9870518 0 0.1604024 -0.2782205 0 0.9605172 0.9967574 0 -0.08046638 0.9870519 0 0.1604018 -0.0402376 0 0.9991902 0.9485352 0 -0.316672 -0.04023772 0 0.9991902 0.9967574 0 -0.08046603 0.2000248 0 0.9797909 0.2000196 0 0.979792 0.9485342 0 -0.3166748 0.8452042 0 -0.5344437 0.428672 0 0.9034602 0.8452035 0 -0.5344448 0.6324648 0 0.7745891 0.692711 0 -0.7212153 0.6324685 0 0.7745862 0.7994304 0 0.6007589 0.6927078 0 -0.7212184 0.7994275 0 0.6007627 0.5000078 0 -0.866021 0.5000072 0 -0.8660213 0.2782132 0 -0.9605194 0.2782128 0 -0.9605195 0.04026782 0 -0.999189 0.04026168 0 -0.9991893 -0.2000278 0 -0.9797903 -0.2000333 0 -0.9797892 -0.4287063 0 -0.903444 -0.4287008 0 -0.9034466 -0.6324332 0 -0.7746149 -0.6324412 0 -0.7746084 -0.7994518 0 -0.6007304 -0.9199686 0 -0.3919923 -0.919968 0 -0.3919938 -0.9870499 0 -0.1604138 -0.9870498 0 -0.1604145 -0.9967564 0 0.08047884 -0.9967564 0 0.08047831 -0.9485387 0 0.3166614 -0.9485381 0 0.3166629 0 1 -7.60086e-6 0 1 -1.52013e-6 0 1 -1.90019e-6 0 1 7.60063e-7 0 1 -1.52016e-6 0 1 -3.04025e-6 0 1 7.60089e-6 0 1 -7.60063e-6 0 1 -3.04033e-6 0 1 -3.0404e-6 0 1 7.60063e-6 0 1 -7.6004e-6 0 1 7.60075e-6 0 1 4.75039e-6 0 1 6.08091e-6 0 1 -3.80043e-6 0 1 -6.08036e-6 0 1 -6.08028e-6 0 1 3.80026e-6 0 1 -9.50079e-7 0 1 3.80043e-6 0 1 3.04029e-6 0 1 -1.90016e-6 0 1 -4.75025e-7 0 1 -6.0808e-6 0 1 3.0404e-6 0 1 -1.90027e-6 0 1 3.04033e-6 0 1 1.14012e-6 -0.8451814 0 0.5344797 -0.8451817 0 0.5344792 -0.6927322 0 0.721195 -0.6927325 0 0.7211946 0.9199672 0 0.3919955 -0.5000007 0 0.866025 0.9199707 0 0.3919873 0.9870567 0 0.1603723 -0.499993 0 0.8660294 -0.2782251 0 0.9605159 0.9870569 0 0.1603707 -0.2782258 0 0.9605157 0.9967564 0 -0.08047866 -0.04026764 0 0.999189 -0.0402677 0 0.999189 0.9967563 0 -0.08047962 0.9485429 0 -0.316649 0.2000116 0 0.9797936 0.9485427 0 -0.3166493 0.8452028 0 -0.5344459 0.428695 0 0.9034493 0.8452037 0 -0.5344443 0.6324706 0 0.7745845 0.6927247 0 -0.7212022 0.6324765 0 0.7745797 0.7994344 0 0.6007536 0.6927268 0 -0.7212001 0.7994341 0 0.600754 0.499977 0 -0.8660387 0.4999728 0 -0.8660411 0.2782309 0 -0.9605143 0.2782251 0 -0.9605159 0.04026281 0 -0.9991891 -0.200026 0 -0.9797906 -0.2000207 0 -0.9797918 -0.428686 0 -0.9034536 -0.4286904 0 -0.9034515 -0.6324463 0 -0.7746043 -0.632447 0 -0.7746037 -0.7994357 0 -0.6007518 -0.79944 0 -0.6007461 -0.9199874 0 -0.3919481 -0.9199857 0 -0.391952 -0.9870471 0 -0.1604311 -0.9870469 0 -0.1604325 -0.9967564 0 0.08047872 -0.9967564 0 0.08047866 -0.9485381 0 0.3166632 -0.9485383 0 0.3166629 0 1 -1.63484e-5 0 1 9.72568e-6 0 1 -1.0731e-6 0 1 -1.78638e-6 0 1 2.22284e-5 0 1 -5.72344e-6 0 1 -5.98871e-7 0 1 -3.27011e-5 0 1 3.26904e-5 0 1 -1.23471e-6 0 1 5.27115e-7 0 1 -8.54255e-6 0 1 -1.90007e-6 0 1 6.1243e-6 -0.5726598 0.0223695 0.819488 -0.5734024 0.01158654 0.819192 -0.8264511 0.05604171 0.5602125 -0.7969403 -0.001852571 0.6040552 -0.9793252 -0.00538963 0.2022209 -0.9743254 -0.03171885 0.2228993 -0.9975282 0.04929798 -0.05007141 -0.9532554 0.02580249 -0.3010622 -0.9722852 -0.0432136 -0.2297695 -0.4931204 0.5016289 0.7107747 -0.4900621 0.5136664 0.7042628 -4.22491e-5 -1 -4.53766e-5 4.45848e-5 -1 1.02754e-4 -3.52872e-6 -1 0 -5.42055e-5 -1 -3.53407e-5 8.59645e-5 -1 -9.00187e-5 5.39606e-5 -1 -3.54547e-5 2.95817e-5 -1 5.28728e-5 -6.45283e-5 -1 -1.0318e-5 -4.47986e-5 -1 -2.20965e-5 5.66442e-4 -0.9999998 -3.16722e-4 -4.58514e-5 -1 5.66136e-5 -4.35453e-6 -1 -1.72957e-5 -4.7862e-5 -1 -2.60291e-5 1.07831e-4 -1 8.8993e-5 1.24723e-5 -1 -8.37984e-6 5.7992e-4 -0.9999999 -2.39226e-4 3.65638e-5 -1 1.09563e-5 -6.68911e-5 -1 -3.37629e-5 0 -1 3.57564e-5 2.85207e-5 -1 -8.27991e-5 5.04228e-6 -1 -4.94137e-6 2.4848e-6 -1 -6.15214e-6 5.3353e-6 -1 3.75899e-6 -0.001417815 -0.9999973 0.001868247 4.05194e-4 -0.9999998 5.60566e-4 1.3217e-4 -1 1.00631e-4 6.04789e-4 -0.9999998 3.44941e-4 7.69639e-6 -1 0 -5.83015e-5 -1 -3.6991e-5 2.9561e-4 -1 2.58104e-5 -2.16371e-5 -1 3.07902e-5 -5.41057e-6 -1 4.01671e-6 -1.37332e-6 -1 1.92588e-5 3.63637e-5 -1 1.20505e-5 3.06345e-5 -1 -2.7166e-5 -6.80996e-6 -1 0 4.74096e-5 -1 4.49576e-6 -6.226e-6 -1 0 -6.08702e-5 -1 -1.47911e-5 4.96143e-5 -1 3.90361e-5 1.79313e-5 -1 3.81294e-5 -1.86246e-6 -1 0 1.02495e-5 -1 3.22596e-5 2.71392e-6 -1 2.7684e-6 1.49722e-5 -1 2.43311e-5 -4.50673e-5 -1 -1.49838e-5 5.28107e-6 -1 -7.73926e-5 -8.24537e-6 -1 3.47524e-6 -1.45936e-5 -1 -1.95357e-5 -2.49199e-6 -1 -7.86757e-6 -4.81636e-5 -1 0 4.38952e-6 -1 8.43217e-6 -6.25369e-7 -1 4.02332e-5 6.66968e-7 -1 3.14898e-6 -3.6946e-7 -1 4.58614e-5 -1.33355e-4 -1 -1.40977e-5 5.12972e-5 -1 3.40383e-5 1.49462e-6 -1 1.4477e-6 4.12776e-6 -1 -8.65027e-6 -4.72177e-5 -1 -2.16202e-5 4.04807e-5 -1 2.06782e-5 -2.52512e-6 -1 2.20478e-6 -5.80944e-5 -1 -5.38477e-5 -4.472e-5 -1 -1.82963e-5 -3.57687e-5 -1 -3.84601e-5 -1.29271e-5 -1 1.44434e-5 5.63133e-5 -1 1.15618e-5 3.12735e-5 -1 3.77177e-5 -4.05004e-6 -1 -6.10113e-6 -6.50859e-6 -1 -6.0576e-6 1.67908e-5 -1 -1.98185e-5 1.18044e-5 -1 -2.57748e-6 -1.22775e-4 -1 7.50751e-5 7.64314e-6 -1 -7.34299e-6 2.10287e-6 -1 0 3.30251e-5 -1 2.15545e-5 -6.32783e-5 -1 5.48326e-5 -3.46457e-5 -1 -5.59301e-5 5.59534e-5 -1 3.46196e-5 -9.69226e-5 -1 -6.19579e-5 1.89337e-5 -1 -2.25144e-5 3.12469e-5 -1 -4.46708e-5 2.05508e-6 -1 -3.25831e-6 -7.25765e-6 -1 5.41687e-6 -1.65155e-6 -1 4.91491e-6 9.09944e-5 -1 9.22639e-5 -9.19691e-5 -1 -1.86893e-4 -1.35028e-5 -1 1.02087e-5 0.5652248 0.04753857 0.8235661 0.609719 -0.02089405 0.7923423 0.2019752 -0.0165255 0.9792513 0.2227902 -0.04698139 0.9737337 -0.04929667 0.04886686 0.9975881 -0.292515 0.02126967 0.9560244 -0.2260313 -0.04672604 0.9729988 -0.8255723 0.02102673 -0.5639045 -0.8221494 0.001709699 -0.5692692 -0.8218988 -0.002067387 -0.5696297 -0.7020651 0.5091331 0.4978838 -0.7190514 0.4954856 0.4872978 -0.8392287 0.5187798 0.1629814 -0.8337661 0.5252025 0.1702839 -0.8233067 0.5278419 -0.208684 -0.8703389 0.4901911 -0.04714816 -0.8253576 0.5028856 -0.2566923 0.506406 0.4995316 0.7028664 0.4936285 0.4828228 0.7233347 0.1729965 0.5110946 0.841935 0.1804362 0.5174195 0.8364927 -0.1984819 0.527478 0.8260581 -0.03781586 0.486445 0.8728926 -0.2481348 0.5028638 0.8279839 0.01234781 0.9998976 -0.007237315 0.0123316 0.9998977 -0.007249176 0.01226419 0.9998987 -0.007227599 0.01237517 0.9998973 -0.0072425 0.01243013 0.9998964 -0.007267296 0.01234579 0.9998983 -0.00716108 0.01238858 0.9998977 -0.007157683 0.01232063 0.9998986 -0.007151186 0.01239699 0.9998976 -0.007154881 0.04476517 0.9989787 0.006144523 0.01235991 0.999898 -0.007161617 0.01236486 0.9998981 -0.007138073 0.01236265 0.9998981 -0.007140517 0.01236659 0.999898 -0.00714147 0.01237034 0.9998981 -0.007133901 0.01076048 0.9999161 -0.007208466 0.01225334 0.9998993 -0.007168889 0.006336688 0.9999799 -3.8209e-4 0.008972585 0.9999434 -0.005727708 0.01227271 0.9998988 -0.007204651 0.01391363 0.9998497 -0.0103386 0.01210522 0.9998957 -0.007888078 0.009058535 0.9999547 -0.002942144 0.01237469 0.9998968 -0.007306396 0.01045918 0.9999442 0.001503467 0.01571857 0.9998054 -0.01192086 0.01271349 0.9998991 -0.006342709 0.01268482 0.9998998 -0.006291687 0.01236999 0.9998981 -0.007126629 0.01342338 0.9998834 -0.007288694 0.01305091 0.9998938 -0.006493687 0.01237297 0.9998978 -0.007166266 0.01249665 0.9998972 -0.007045626 0.01329988 0.9998875 -0.006934702 0.01246446 0.9998965 -0.007189571 0.008823394 0.9999604 -0.001187741 0.01234388 0.9998985 -0.007128834 0.01247572 0.9998965 -0.007167816 0.01246803 0.9998971 -0.007107138 0.0124402 0.9998968 -0.007206022 0.01239657 0.9998978 -0.007123172 0.01238876 0.9998983 -0.007065832 0.01240128 0.9998981 -0.007068097 0.01233863 0.9998991 -0.007052659 0.0120725 0.9999043 -0.00676316 0.01224511 0.9999007 -0.006972491 0.01200252 0.9999062 -0.006600856 0.0165838 0.9997913 -0.01193642 -0.563876 -0.8224939 -0.0744825 -0.511612 -0.8406627 -0.1775935 -0.6449338 -0.7551972 0.1172072 -0.6185856 -0.7852417 0.02734285 -0.7167856 -0.5895299 0.3723883 -0.7102779 -0.432402 0.5554584 -0.7170746 -0.593837 0.3649132 -0.6502481 -0.1861723 0.7365577 -0.7076045 -0.3740076 0.5995118 -0.6153587 -0.07234048 0.7849208 -0.430862 -0.8554081 -0.2874634 -0.433022 -0.8529255 -0.291565 -0.2652044 -0.8298026 -0.4910134 -0.2513064 -0.8218988 -0.511202 -0.04399514 -0.7156018 -0.6971216 -0.03854101 -0.7110145 -0.7021204 0.06543534 -0.6358597 -0.7690258 0.124412 -0.5947705 -0.7942101 0.2742246 -0.4443669 -0.8528417 0.2688072 -0.452063 -0.8505185 0.3682825 -0.3266409 -0.8704446 0.5117363 -0.1213862 -0.8505242 0.4637616 -0.2092008 -0.8609066 -0.811553 0.03464591 -0.5832509 -0.8171172 0.003201723 -0.5764628 -0.814139 0.04240268 -0.5791198 -0.5605489 0.06062573 -0.8258993 -0.6106094 -0.02804946 -0.7914351 -0.2025714 -0.03211206 -0.9787408 -0.2225487 -0.06863731 -0.9725025 0.05043232 0.04637444 -0.9976503 0.2984443 0.01537704 -0.9543033 0.2208151 -0.08153754 -0.9719014 0.5744093 0.02343612 -0.8182327 0.5714927 -0.04115694 -0.8195744 0.8291754 0.0551815 -0.5562582 0.7927092 -0.05593407 -0.6070284 0.9783634 -0.04545658 -0.2018387 0.9707928 -0.09075278 -0.2220932 0.9975037 0.0505585 0.04929751 0.9519604 0.02650946 0.3050717 0.9695496 -0.0961917 0.225213 0.8172382 0.01175403 0.5761802 0.8190119 -0.005606591 0.5737491 0.8191133 -0.005748987 0.573603 0.8209497 -0.008026778 0.5709442 0.819392 -0.02318221 0.5727647 0.8191258 -0.00444889 0.5735967 -0.1778526 -0.007092058 0.9840316 -0.26007 0.01708221 0.9654387 -0.7403427 -0.01894193 -0.6719627 -0.7227232 0.006163418 0.6911101 -0.6961796 0.0188803 0.7176193 -0.3515988 -0.009936034 -0.9360982 -0.4736643 0.02882486 -0.8802338 -0.9733393 0.005794644 0.2292974 0.1312401 -0.01660615 -0.9912115 -0.9881023 0.02731001 0.1513542 0.2102319 0.004304647 -0.9776421 -0.9694427 -9.40181e-4 -0.2453162 0.5738843 -0.02406728 -0.8185828 -0.9262688 0.0267266 -0.3759147 0.658671 -0.002083718 -0.7524282 0.910449 -0.03036504 -0.4125055 0.9426627 -0.007073283 -0.3336721 0.9791178 -0.01821237 0.2024762 0.9860734 -0.006059527 0.1662002 0.7410929 -0.01221406 0.6712914 0.6854239 0.01063412 0.7280667 0.3476613 -0.008792519 0.9375791 0.2456554 0.01539605 0.969235 -0.1775513 -0.007807552 0.9840806 -0.2600627 0.01744949 0.9654341 -0.740328 -0.01999956 -0.6719482 -0.7225433 0.005828917 0.6913011 -0.6961738 0.01904523 0.7176206 -0.351558 -0.0102604 -0.93611 -0.4736472 0.03014266 -0.8801988 -0.9734132 0.005436062 0.228992 0.131363 -0.01695501 -0.9911894 -0.9880846 0.02785724 0.1513699 0.2102584 0.004888594 -0.9776337 -0.9694069 -0.001424372 -0.2454552 0.5736903 -0.02456486 -0.8187039 -0.9262722 0.02754193 -0.3758474 0.6586147 -0.001526236 -0.7524788 0.9103828 -0.03113603 -0.4125939 0.9426944 -0.006764173 -0.3335889 0.9791265 -0.01856207 0.2024025 0.9860972 -0.005836963 0.1660673 0.7409855 -0.01254677 0.6714038 0.6854103 0.01122784 0.7280706 0.3476745 -0.009279787 0.9375694 0.2456759 0.01590085 0.9692217 0.6261674 -0.003246724 0.7796819 0.592923 0.00316137 0.8052531 0.2800636 -0.002467215 0.9599783 0.200335 0.01096224 0.9796661 -0.1896927 0.003276467 0.9818381 -0.2475923 0.0116859 0.9687938 0.8196774 -0.002475202 0.5728202 0.8190302 -0.005727708 0.573722 0.9721591 -0.002300381 0.2343108 0.9409554 -0.013022 0.3382799 0.9997978 -0.01911807 0.00624597 0.9774534 -0.00517559 -0.2110878 0.9434736 -0.01908183 -0.330898 0.8051174 -0.009729981 -0.5930358 0.7621099 -0.01627171 -0.6472432 0.568924 -0.01256614 -0.8222942 0.5735856 -0.01106578 -0.8190709 0.5732272 -0.01196056 -0.8193092 0.5734438 -0.01366317 -0.819131 0.5743321 -0.01252543 -0.8185268 0.5734905 -0.01372534 -0.8190973 -0.6029486 0.004219174 -0.797769 -0.5918768 0.005121707 -0.8060123 -0.3491388 -0.006009936 -0.9370518 -0.01938289 -0.01192927 -0.999741 -0.2163916 0.00167185 -0.9763053 0.3411496 -0.01309663 -0.9399178 0.2410172 -0.004644513 -0.9705098 -0.8189505 0.007097005 -0.5738202 -0.8190253 0.006849348 -0.5737167 -0.9698562 0.0156266 -0.2431766 -0.9464785 0.007316231 -0.3226841 -0.9788078 0.01924288 0.2038753 -0.9966716 0.006604254 0.08125299 -0.7975472 0.01689207 0.6030201 -0.8500543 0.009535491 0.5266088 -0.5733068 0.01336222 0.8192319 -0.5724562 0.01422607 0.8198119 -0.5736626 0.01102626 0.8190175 -0.588886 0.01897108 0.8079935 -0.5730008 0.01379191 0.8194389 -0.5742332 0.0155813 0.8185436 -0.1776851 -0.005680322 0.984071 -0.2600564 0.01649105 0.9654527 -0.7404476 -0.01698464 -0.6718995 -0.722653 0.006856024 0.6911771 -0.6962395 0.01839232 0.7175738 -0.3518297 -0.009249448 -0.9360184 -0.4735139 0.02624773 -0.8803953 -0.9733366 0.006475746 0.2292903 0.1314476 -0.01590788 -0.9911955 -0.9881337 0.02607935 0.1513657 0.2101594 0.003082513 -0.9776624 -0.9694418 1.21405e-5 -0.2453214 0.5739156 -0.02312928 -0.8185878 -0.9263027 0.02518832 -0.3759375 0.6587501 -0.003052115 -0.7523557 0.9104536 -0.02899944 -0.4125935 0.9426845 -0.007693588 -0.333597 0.9791374 -0.01756638 0.2024387 0.9860883 -0.00643897 0.1660971 0.7411497 -0.01154655 0.6712405 0.685525 0.009438812 0.727988 0.3480172 -0.007819771 0.9374556 0.2458505 0.01443028 0.9692004 -0.1775492 -0.005130469 0.9840986 -0.2600562 0.01626944 0.9654565 -0.7403632 -0.01619011 -0.6720122 -0.7225449 0.007156193 0.6912871 -0.6962604 0.01820653 0.7175584 -0.351534 -0.008996367 -0.9361319 -0.4735499 0.0252977 -0.8804036 -0.9733285 0.006753027 0.2293166 0.1314068 -0.01565068 -0.991205 -0.9881293 0.02557832 0.1514806 0.2101176 0.002596676 -0.9776727 -0.9694412 4.09076e-4 -0.2453235 0.5737358 -0.02277374 -0.8187237 -0.9263718 0.02457666 -0.3758075 0.6587284 -0.003417551 -0.7523732 0.9104993 -0.02848923 -0.412528 0.9426886 -0.007908046 -0.3335804 0.979134 -0.01732432 0.2024765 0.9860757 -0.006614804 0.166166 0.7410201 -0.01125907 0.6713885 0.6855655 0.008924901 0.7279562 0.3477957 -0.007431149 0.937541 0.2458009 0.01401704 0.9692191 -0.7078538 0.5054212 -0.4934496 -0.7081987 0.5049051 -0.4934831 -0.7092329 0.5014424 -0.4955243 0.7191709 0.4825886 0.4999014 0.7032853 0.5049547 0.5004104 0.5569505 8.13932e-4 0.8305454 0.4783062 -0.003910958 0.8781844 0.1763464 0.008839607 0.9842885 -0.1072074 0.01141071 0.9941712 0.05495345 0.005974829 0.9984711 -0.4398353 0.01421761 0.897966 -0.2892606 0.007784724 0.9572188 -0.5744646 0.01346266 0.8184188 -0.5740602 0.01367628 0.8186989 -0.573709 0.01398265 0.8189399 -0.573184 0.01448398 0.8192987 -0.5724477 0.01111578 0.8198659 -0.573639 0.01395875 0.8189893 -0.5765685 0.01254159 0.8169527 -0.5728805 0.01284033 0.8195383 -0.5734823 0.01291841 0.8191161 -0.5734552 0.01291036 0.8191352 -0.5734103 0.01252323 0.8191727 -0.5729495 0.01276785 0.8194913 -0.5735383 0.01291006 0.819077 -0.5734812 0.01288998 0.8191174 -0.5734204 0.01293236 0.8191593 -0.5752475 0.0120477 0.8178907 -0.5735187 0.01308321 0.819088 -0.5745992 0.01147425 0.8183547 -0.5734948 0.01292377 0.8191074 -0.5752718 0.01193165 0.8178753 -0.5767925 0.01269125 0.8167921 -0.1733674 0.851761 -0.4944157 -0.4582211 0.8605201 -0.2225729 -0.4957449 0.8629308 0.0979157 -0.2841958 0.8612781 0.421228 0.106324 0.8528508 0.5112151 0.473326 0.846486 0.2437705 0.5158424 0.8477948 -0.1230882 0.2698547 0.8390876 -0.4723458 -0.4705159 -0.8741444 0.1203601 -0.3087027 -0.9397027 0.1471785 -0.442286 -0.8798449 -0.1739435 -0.5980651 -0.6665534 0.4449998 -0.6337464 -0.710661 0.3054939 -0.2908296 -0.7857496 0.5459083 -0.4727527 -0.4487537 0.7583701 -0.6874172 -0.3521541 0.6351733 -0.2522124 -0.9537699 -0.1634379 -0.2132191 -0.9680779 -0.1317681 -0.6987706 0.504849 -0.5068009 -0.7006977 0.5009711 -0.507987 -0.699191 0.5033762 -0.5076853 0.04551076 0.9986057 0.02674961 0.01238119 0.999898 -0.007135987 0.01224011 0.9998996 -0.007153868 0.01237851 0.9998979 -0.007138311 0.01240766 0.9998977 -0.007131695 0.01237344 0.999898 -0.007140159 0.01244145 0.9998971 -0.007136881 0.01131045 0.9999202 -0.005647718 0.01786398 0.9997729 -0.01162642 0.01230603 0.9998989 -0.00713545 0.01223826 0.999899 -0.007233142 0.01234698 0.9998984 -0.007130265 0.01240843 0.9998976 -0.007129192 0.01234757 0.9998984 -0.007138729 0.01239955 0.9998978 -0.00712198 0.01222175 0.9998996 -0.007176458 0.0123282 0.9998995 -0.007011353 0.01249569 0.9998969 -0.007078588 0.01224172 0.9998992 -0.00719881 0.01234751 0.999899 -0.007041454 0.01244384 0.9998968 -0.007183134 0.01240479 0.9998982 -0.007050335 0.01238936 0.9998986 -0.007035255 0.01287204 0.9998865 -0.007837653 0.01690351 0.9997798 -0.01243805 0.01226621 0.9998996 -0.007115304 0.01226657 0.9998996 -0.007115602 0.01231086 0.9998992 -0.007080912 0.01235133 0.9998993 -0.006997108 0.01175326 0.9999073 -0.006879329 0.01094251 0.9999244 -0.005619525 0.01220202 0.9999001 -0.007156908 0.01147896 0.9999161 -0.006002545 0.01240366 0.9998978 -0.00711143 0.01237267 0.9998986 -0.007059454 0.01235008 0.9998991 -0.007031798 0.01234525 0.9998992 -0.007013142 0.01639604 0.9997118 -0.01754111 0.01170682 0.999913 -0.006077349 0.01262438 0.999893 -0.007389962 0.01241934 0.9998975 -0.007130742 0.01227986 0.9999017 -0.006786227 0.01244258 0.9998977 -0.007066607 0.01181697 0.99991 -0.006362259 0.01247912 0.9998968 -0.007127404 0.01235151 0.9998998 -0.006922304 0.01247453 0.9998958 -0.007284164 0.01244235 0.9998969 -0.007179796 0.03939956 -0.9146923 -0.402226 -0.1326108 -0.8954541 -0.4249429 -0.01060134 -0.9935694 -0.1127283 0.2724432 -0.6994192 -0.6607477 0.2714141 -0.799126 -0.5364067 -0.05945181 -0.6364169 -0.7690508 0.2704264 -0.3748749 -0.8867573 0.4981498 -0.4282135 -0.7539762 0.5737803 -0.01136535 -0.8189304 0.5745422 -0.01477086 -0.8183417 0.5733505 -0.01191389 -0.8192237 0.5734985 -0.01299679 -0.8191036 0.5735018 -0.01295697 -0.8191019 0.5734941 -0.0128836 -0.8191084 0.5717257 -0.01388806 -0.8203273 0.5735833 -0.01336866 -0.8190382 0.5723726 -0.01436704 -0.8198678 0.5734261 -0.01298946 -0.8191544 0.5716204 -0.01391673 -0.8204002 0.5702085 -0.01328659 -0.8213926 0.5735426 -0.01295179 -0.8190733 0.5734751 -0.01296615 -0.8191204 0.5741157 -0.01302832 -0.8186706 0.5736468 -0.01297587 -0.8190001 0.5739548 -0.01316362 -0.8187813 0.5733066 -0.01191335 -0.8192543 0.5731413 -0.01204007 -0.8193683 0.5727813 -0.01227051 -0.8196164 0.5723226 -0.01251631 -0.8199332 0.5704106 -0.01333773 -0.8212515 -0.4970173 0.5051032 -0.7055811 -0.4816459 0.4844925 -0.7302631 -0.1604779 0.5031626 -0.849161 -0.1677311 0.5097494 -0.8438139 0.207707 0.509894 -0.834785 0.04967463 0.4728639 -0.8797342 0.2657677 0.4806721 -0.8356565 0.5021162 0.4934054 -0.7102327 0.5021547 0.4933152 -0.7102683 0.7655506 0.5311245 -0.3630964 0.7419176 0.4499667 -0.4970799 0.8571535 0.5136431 0.03819102 0.8690293 0.4600536 -0.1820405 0.8573321 0.513305 0.03872728 0.8533498 0.4545641 0.2552754 0.1156182 0.9911382 0.06540316 0.08252078 0.9955404 0.04571354 0.4121135 0.8672427 0.2793791 0.3199246 0.9250476 0.2047808 0.6083514 0.6787771 0.4113031 0.5669125 0.7259588 0.3893508 0.7621536 0.3683317 0.5324038 0.7210235 0.4873272 0.4925823 0.8198669 0.06480318 0.5688752 0.8153245 0.108557 0.5687366 0.7124116 0.5267317 0.4637062 0.7219569 0.4839492 0.4945416 0.9881095 -0.01509147 0.1530097 0.9720326 -0.008833825 0.2346801 0.954761 -0.01425027 -0.2970324 0.9851735 -0.009007573 -0.1713247 0.8942175 -0.01111465 -0.447495 0.8004199 -0.01661545 -0.5992094 0.6926811 -0.01137989 -0.7211542 -0.1836425 0.9434702 0.2759338 -0.1488142 0.9637454 0.2214704 -0.3957405 0.7144457 0.5770242 -0.3528023 0.7860305 0.5076286 -0.5346629 0.3512912 0.7685897 -0.521313 0.4172293 0.7444142 0.01351898 0.999884 -0.007036864 0.01253002 0.9998983 -0.006831467 0.1621196 0.9611635 -0.2233426 0.2155117 0.9312266 -0.2938905 0.3365881 0.8124489 -0.4760625 0.4709281 0.5735553 -0.6702694 0.4207618 0.6901203 -0.5888069 0.5572512 0.2389256 -0.7952268 0.5442602 0.3333309 -0.7698516 0.562065 0.2524647 -0.7876195 0.5237858 0.3329948 -0.7840682 0.4874068 0.593701 -0.6402764 0.3746128 0.7045109 -0.6027683 0.3615128 0.8267769 -0.4309856 0.162657 0.9317309 -0.324685 -0.8191271 0.006019294 -0.5735806 -0.8191025 0.006012141 -0.5736159 -0.8190873 0.00605607 -0.5736369 -0.8191387 0.00600177 -0.5735642 -0.8191418 0.006016969 -0.5735595 -0.8190898 0.00604707 -0.5736337 -0.8191207 0.005983054 -0.5735899 -0.8191226 0.006040751 -0.573587 -0.8191167 0.006090462 -0.5735946 -0.8191097 0.006045818 -0.5736052 -0.8191077 0.00603187 -0.5736081 -0.8191258 0.006147503 -0.5735812 -0.8191116 0.006022512 -0.5736027 -0.8191084 0.006067693 -0.5736068 -0.8191018 0.006047666 -0.5736165 -0.8190981 0.006037294 -0.5736218 -0.8191135 0.005925297 -0.5736011 -0.8191161 0.006019711 -0.5735964 -0.8191128 0.00606507 -0.5736005 -0.8191229 0.006035327 -0.5735864 -0.8191145 0.005971252 -0.573599 -0.8191329 0.00603491 -0.5735722 -0.8191128 0.005985856 -0.5736013 -0.8191133 0.006004512 -0.5736004 -0.8191334 0.005989611 -0.573572 -0.8191109 0.005960643 -0.5736042 -0.8191285 0.006126642 -0.5735774 -0.8191139 0.006063282 -0.5735989 -0.8191224 0.006036698 -0.5735871 -0.8191121 0.006088674 -0.5736014 -0.8191196 0.006032407 -0.573591 -0.819118 0.006001651 -0.5735937 -0.8191298 0.006033897 -0.5735765 -0.8191155 0.006070733 -0.5735966 -0.8190703 0.006023883 -0.5736615 -0.8191072 0.006077527 -0.5736085 0.4650646 -0.01229315 -0.8851915 0.4507889 -0.01131868 -0.8925588 0.07026839 -0.007842898 -0.9974973 0.08671396 -0.008926331 -0.9961933 -0.1688187 -0.00378412 -0.9856399 -0.1388952 -0.005649209 -0.9902911 -0.537723 0.003540158 -0.8431142 -0.4486219 -0.002759337 -0.8937174 -0.7243894 0.003799557 -0.6893805 0.1954573 -0.9374015 -0.2882276 0.180526 -0.9463106 -0.2681543 0.4053561 -0.7020223 -0.585535 0.391588 -0.7242546 -0.567551 0.5371647 -0.343754 -0.7702516 0.5311893 -0.3682293 -0.7630499 -0.004021108 0.9998337 -0.01779407 -0.5195889 0.3874828 0.7615014 -0.5215215 0.3969161 0.7552966 -0.4139021 0.7194365 0.55776 -0.3158386 0.8742263 0.3687473 -0.3421723 0.7837289 0.5183506 -0.1196476 0.9648171 0.2341209 -0.1184632 0.9903567 0.07183539 -0.6315798 0.01788574 0.7751046 -0.7008586 0.01280629 0.7131853 -0.8437202 0.01138502 0.5366624 -0.8991481 0.0168851 0.437319 -0.9878624 0.01298993 0.1547877 -0.9831224 0.01473611 0.1823549 -0.9961753 0.01096308 -0.08668798 -0.9974498 0.01198112 -0.07036006 -0.8832522 0.007119178 -0.4688442 -0.8922421 0.008441329 -0.4514784 -0.09466314 -0.9879421 0.1225129 -0.2009825 -0.9390525 0.2789023 -0.3067756 -0.8508858 0.4264767 -0.4181937 -0.691411 0.5891222 -0.4060906 -0.7121469 0.572658 -0.5080198 -0.4748597 0.7186266 -0.5383896 -0.3483208 0.7673392 -0.5697262 -0.1361524 0.810478 -0.02211004 0.8149061 0.5791712 0.06110364 0.968489 0.2414446 0.07204395 0.3251056 0.9429295 0.09243184 0.4705946 0.8774949 0.3350512 0.858341 0.3885761 0.2707543 0.8753675 0.4005296 0.1012675 0.8085834 0.5796015 0.1973068 0.2076203 0.9581044 0.5136238 0.6749044 0.5298064 0.4796658 0.6943739 0.536438 0.274963 0.5509809 0.7879185 0.2866064 0.6410046 0.7120183 0.5686751 0.09365177 0.8172136 0.6874175 0.3654972 0.6275899 0.6926352 0.1921871 0.6952127 0.6085425 0.4423153 0.6588119 0.413433 0.2781622 0.8670058 0.4233924 0.411825 0.8069319 -0.376761 0.4484492 0.8105211 -0.4504135 0.1037878 0.8867671 -0.3122977 0.4420471 0.8408713 -0.2559862 0.2733517 0.927227 -0.1587078 0.6006304 0.7836167 -0.1692508 0.7164309 0.6768169 -0.1495964 0.231969 0.961151 -0.1060785 0.9424251 0.3171472 -0.1916583 0.939517 0.2838577 -0.1920006 0.9393121 0.2843036 -0.4055104 0.7020602 0.5853826 -0.3931682 0.7217651 0.5696262 -0.4784135 0.5421128 0.6908214 -0.5394667 0.3364791 0.7718533 -0.5357483 0.3521571 0.7674369 -0.5637825 0.1636866 0.8095408 -0.1797826 -0.9607707 0.211182 -0.2011953 -0.9390417 0.2787854 -0.3277965 -0.8200622 0.4690921 -0.4135035 -0.720629 0.5565148 -0.4160542 -0.7119976 0.5656486 -0.4988549 -0.4879314 0.7162868 -0.5496044 -0.337483 0.7642254 -0.5496084 -0.3436096 0.7614875 -0.5660858 -0.1256595 0.8147127 0.3956941 -0.8780736 0.2690964 0.157059 -0.9765746 0.1470873 0.04198271 -0.9988121 0.02473461 -0.762087 0.3696077 -0.5316143 -0.2643973 -0.9503178 -0.1642875 -0.7650075 0.3455343 -0.5434792 -0.2295467 -0.9614596 -0.1513405 -0.492899 0.7957661 -0.3518621 -0.4594765 -0.8170895 -0.3482042 -0.5367922 0.7376701 -0.4095084 -0.5356848 -0.7588268 -0.3704375 -0.7202833 -0.4914736 -0.4895364 -0.8110182 -0.1779658 -0.5572949 -0.7473073 -0.3997164 -0.5308094 -0.1700719 0.9771913 -0.1271729 -0.8085955 -0.06587332 -0.5846658 -0.1978278 0.9668993 -0.1611521 0.1327809 0.9904201 0.03791528 0.1941844 0.9744099 0.1132161 0.4495408 0.8381659 0.3088546 0.5253465 0.7796012 0.3409298 0.6627697 0.6096792 0.4347732 0.6899093 0.5374236 0.4849755 0.8110869 0.1686608 0.5600819 0.8080158 0.1070124 0.5793607 0.8142826 -0.157187 0.558781 0.7443575 -0.3802093 0.5489743 0.6873838 -0.555201 0.4682471 0.5099335 -0.7662401 0.3909529 -0.01747906 -0.9998319 0.005550384 -0.02856642 -0.9995537 -0.008737385 0.2542729 0.8464311 -0.4678673 -0.5101209 0.860086 -0.005372822 -0.1344522 0.8538469 -0.5028601 -0.3896754 0.8599032 -0.3297266 -0.3509383 0.8651759 0.3582081 -0.08775407 0.8624143 0.4985389 0.2606849 0.8549022 0.4485373 0.4857196 0.8515112 -0.1974973 0.512281 0.8490658 0.1290567 0.06888318 -0.9923808 -0.1021544 0.258251 -0.871923 -0.4160008 0.213141 -0.9320229 -0.293094 0.4515445 -0.5846315 -0.6740279 0.4176845 -0.7079269 -0.569543 0.5494132 -0.3234641 -0.7704001 0.4975538 -0.4229085 -0.7573564 0.5715104 -0.1174679 -0.8121436 0.2143158 0.9308768 -0.295867 0.2150707 0.9303215 -0.2970635 0.4113255 0.7036395 -0.5793988 0.5089281 0.4732322 -0.7190574 0.4216629 0.6833272 -0.5960407 0.5696985 0.1435757 -0.8092156 0.5449742 0.3119218 -0.7782726 -0.1642793 0.9767339 -0.137852 -0.8166359 -0.02729088 -0.5765077 -0.6306526 0.6811792 -0.3718498 -0.1538317 0.9788367 -0.1349623 -0.7429865 -0.4553978 -0.4904937 -0.8222729 -0.08377099 -0.5628941 -0.4120145 0.8618207 -0.2958198 -0.6668163 0.5665315 -0.4841468 -0.7568038 -0.3995729 -0.5172908 -0.5897338 -0.6971474 -0.4076759 -0.7904003 -0.5054209 -0.346146 -0.6391555 0.5975039 -0.4842204 -0.7798001 0.308737 -0.5446038 -0.5735319 -0.7234288 -0.3843333 -0.2132547 -0.9644513 -0.1560648 -0.361257 -0.9065883 -0.2181537 0.2095993 -0.9383174 0.2750065 0.001976549 -0.9996969 0.02454185 0.3571455 -0.8980261 0.2568978 0.381991 -0.8779222 0.2886793 0.6600077 -0.5907799 0.4640787 0.6569918 -0.5980358 0.4590373 0.7699573 -0.3085312 0.5585467 0.8194815 -0.1469156 0.5539549 0.6817086 0.4411493 0.5836616 0.8217808 0.08382624 0.5636041 0.7009714 0.5447015 0.4603688 0.7469536 0.3998019 0.5312429 0.4164273 0.8724858 0.2556499 0.5288513 0.7588402 0.3801025 -0.1236425 0.9922639 0.01117599 0.1873313 0.9745512 0.1231139 0.9531833 0.2973824 0.05482208 0.8946784 0.1788744 0.4093343 0.6902348 0.5864774 -0.4238164 0.7736317 0.5646492 -0.2875161 0.7888944 0.4851838 0.3771502 0.8285136 0.4384916 0.3482677 0.9099621 0.4000252 0.1093116 0.5583816 0.7034406 -0.4397514 0.6487368 0.7144641 0.2620717 0.6784199 0.6898882 0.252588 0.7415466 0.6640807 -0.09542316 0.7766042 0.6298694 0.012268 0.277246 0.9333125 -0.2281718 0.3854519 0.9169188 0.1033768 0.2669163 0.9627003 -0.04431509 0.4880226 0.8683574 0.08825904 0.5115947 0.8261129 -0.2362382 0.5897264 0.799112 -0.1168032 0.6586813 0.1237878 -0.7421694 0.8634434 0.2195495 -0.4541627 0.7460023 0.296095 -0.5964968 0.962052 0.2338433 -0.140618 0.9142041 0.3032159 -0.2688701 0.6895362 0.4177656 -0.591618 0.9638665 0.08411949 0.2527556 0.01236969 0.9998974 -0.00723046 0.01235789 0.9998983 -0.007127642 0.01150947 0.9999082 -0.007156789 0.01152592 0.999911 -0.00672245 0.01143932 0.9999057 -0.007606029 0.01147687 0.999916 -0.006024122 0.01237291 0.9998977 -0.007189691 0.01137661 0.9999047 -0.007832765 0.01193451 0.9998975 -0.007915735 0.01221776 0.9998998 -0.007160186 0.01296144 0.9998825 -0.008188366 0.01365768 0.9998728 -0.008239567 0.01237434 0.999898 -0.007143676 0.01236438 0.9998977 -0.007197678 0.01286214 0.9998835 -0.008225977 0.01171272 0.999916 -0.005565464 0.011913 0.9998992 -0.007725298 0.01236402 0.9998981 -0.007137894 0.01234257 0.9998986 -0.007114946 0.01236581 0.9998984 -0.00709182 0.01229739 0.9998995 -0.007071554 0.01236689 0.9998982 -0.007129609 0.01150804 0.9999141 -0.006288468 0.01238834 0.9998973 -0.007206082 0.01236689 0.9998981 -0.007142186 0.01115089 0.9999228 -0.005494475 0.01125121 0.9999214 -0.005541265 0.01106202 0.9999243 -0.005385339 0.01126354 0.9999212 -0.005556643 0.01139235 0.9999191 -0.005665838 0.01107925 0.999924 -0.005425989 0.01268833 0.9998905 -0.007620155 0.01346117 0.9998886 -0.006463408 0.01233267 0.9998984 -0.007151663 0.01232618 0.9999059 -0.006036996 0.01236522 0.9998978 -0.0071882 0.01225739 0.9998991 -0.007193088 0.01236772 0.9998982 -0.007116138 0.01235157 0.9998984 -0.00712198 0.01235544 0.9998984 -0.007125318 0.01219236 0.9998979 -0.007456839 0.01104056 0.9999071 -0.008009731 0.01341295 0.9998893 -0.006456315 0.009000301 0.9999573 -0.002124965 0.01239627 0.9998978 -0.007134914 0.01237112 0.9998982 -0.007121324 0.01236796 0.9998978 -0.007178723 0.01233762 0.9998985 -0.007139623 0.01237612 0.9998982 -0.007110416 0.01233172 0.9998977 -0.00725454 0.01235026 0.9998978 -0.007198512 0.0123766 0.9998977 -0.007177352 0.01237457 0.9998983 -0.007101893 0.01327872 0.9998912 -0.006445705 0.01232874 0.9998984 -0.007156789 0.01232147 0.9998985 -0.007159233 0.01219326 0.9999031 -0.006736755 0.01228874 0.9998994 -0.007096767 0.01236039 0.9998981 -0.007156193 0.01239389 0.9998972 -0.007214546 0.0123642 0.9998983 -0.007108569 0.01235604 0.9998981 -0.007166206 0.01274782 0.9998953 -0.00684458 0.01451188 0.9998427 -0.01020461 0.01406341 0.9998806 -0.006419539 0.01451444 0.9998426 -0.0102154 0.01400977 0.9998786 -0.006826698 0.01407974 0.9998807 -0.006363868 0.0143581 0.9998491 -0.009788572 0.01451629 0.9998423 -0.01024132 0.01235997 0.9998981 -0.007150888 0.01235789 0.9998982 -0.007135391 0.01237154 0.9998978 -0.007166743 0.01236706 0.9998983 -0.007121145 0.01235198 0.9998985 -0.007100999 0.01255548 0.9998921 -0.007632493 0.01237279 0.9998973 -0.007248461 0.01236397 0.9998981 -0.007140636 0.01236134 0.9998985 -0.007098615 0.01239675 0.9998977 -0.007150948 0.01240098 0.9998975 -0.007156848 0.01241952 0.9998974 -0.007141888 0.0126518 0.9998965 -0.006857752 0.01264113 0.9998964 -0.00689727 0.01207882 0.9999042 -0.00676757 0.01227307 0.9998987 -0.007214844 0.01239854 0.9998978 -0.007116258 0.01307469 0.9998824 -0.008024156 0.01472651 0.9998372 -0.01043164 0.01219421 0.9998996 -0.00722301 0.01237875 0.9998984 -0.007083594 0.01238596 0.999898 -0.0071159 0.01208031 0.999901 -0.007220268 0.01250857 0.9998981 -0.006893932 0.01238393 0.999898 -0.007122159 0.01238143 0.9998978 -0.007146596 0.0123797 0.9998978 -0.007156193 0.01254785 0.9998961 -0.007090747 0.01296126 0.9998834 -0.008094549 0.01236748 0.9998982 -0.007130682 0.01234471 0.9998985 -0.007113635 0.01236426 0.9998979 -0.007173061 0.01235133 0.9998983 -0.007142722 0.01236569 0.9998982 -0.007134079 0.01236259 0.999898 -0.00716567 0.01237756 0.999898 -0.007137417 0.0123673 0.9998981 -0.007139861 0.01193827 0.9998868 -0.009173691 0.01204174 0.9998867 -0.009039342 0.01236826 0.999898 -0.007149517 0.01236373 0.9998981 -0.007138311 0.01235282 0.9998983 -0.007137894 0.01236438 0.9998981 -0.007148385 0.0123642 0.9998982 -0.007127821 0.01236164 0.9998979 -0.007169663 0.01236349 0.9998982 -0.007122457 0.01236504 0.9998981 -0.007147967 0.01237839 0.9998983 -0.007097542 0.01244205 0.9998962 -0.007280647 0.01238006 0.9998978 -0.007164716 0.01237505 0.9998978 -0.007163703 0.01236164 0.9998981 -0.0071401 -0.4846506 0.1855141 -0.854809 -0.347999 0.6446812 -0.6806489 -0.3818568 0.5471157 -0.7448825 -0.5776735 0.3722929 -0.7264237 -0.5652127 0.3732547 -0.7356736 0.3960525 0.3400143 -0.8529552 0.3724466 0.3191275 -0.8714593 0.3219153 0.7000783 -0.637386 0.1470841 0.3070029 -0.9402742 0.09390294 0.9382271 -0.3330348 0.189813 0.7484205 -0.6354824 0.003149867 0.3914976 -0.9201738 0.06192523 0.9460278 -0.3181144 0.03014999 0.709311 -0.7042507 -0.1624212 0.3508074 -0.9222547 -0.2407978 0.2192052 -0.9454975 -0.1847158 0.7539323 -0.6304492 -0.1850498 0.8552737 -0.4840078 -0.01671183 -0.9998018 0.01082032 -0.007347464 -0.9999731 -1.44816e-4 0.396777 -0.7161868 -0.5741467 0.3967758 -0.7161924 -0.5741407 0.3968631 -0.7161405 -0.5741451 -0.01237994 -0.999898 0.007144153 -0.01236337 -0.9998982 0.007130742 -0.01236927 -0.9998981 0.007130265 -0.01235818 -0.9998984 0.007109165 -0.01236599 -0.9998981 0.007144927 -0.01236504 -0.9998982 0.007133781 -0.01236718 -0.9998981 0.007134437 -0.01232266 -0.9998985 0.007161796 -0.01237195 -0.999898 0.007152855 -0.01233774 -0.9998992 0.007036685 -0.01235151 -0.9998986 0.007106661 -0.01236516 -0.9998981 0.007139921 -0.01237004 -0.999898 0.007146537 -0.01236969 -0.9998981 0.007132709 -0.01232361 -0.9998989 0.007100045 -0.414269 -0.6978811 0.584246 -0.4142599 -0.6978937 0.5842373 -0.4142157 -0.697895 0.584267 -0.01012009 -0.9999478 0.001428604 -0.0167846 -0.9997715 0.01323348 -0.8167421 0.01228076 -0.5768722 -0.8204365 0.004997074 -0.5717159 -0.006618261 -0.4062809 -0.9137243 0.1532386 -0.3212903 -0.9345002 -0.3964223 -0.5488204 -0.7359657 -0.1690266 -0.3578095 -0.9183695 -0.5394914 -0.4214146 -0.7289436 -0.2284786 -0.24892 -0.9411889 -0.7320054 -0.09947323 -0.6739979 -0.4550994 -0.1644685 -0.8751198 -0.5579182 -0.2468783 -0.7923247 0.07407158 -0.9344208 -0.3483838 0.00297451 -0.9415419 -0.3368828 0.3028993 -0.7193613 -0.6251172 0.1739466 -0.7622814 -0.6234338 -0.2013756 -0.8619909 -0.4652092 0.3891903 -0.3601865 -0.8478188 -0.2014561 -0.7578499 -0.6205474 0.01258385 -0.719724 -0.6941463 0.3752526 -0.3460376 -0.8599091 -0.3625761 -0.6491204 -0.6687162 -0.8135963 0.07968658 -0.5759439 -0.7084867 0.4909242 -0.5069913 -0.7636495 0.3588425 -0.536723 -0.5752394 0.7049406 -0.4149197 -0.4081452 0.8608554 -0.3038843 -0.563719 0.7193955 -0.4058215 -0.0706827 0.9950301 -0.07013714 -0.2683981 0.9423382 -0.1999031 -0.4599946 0.8682809 0.1857236 -0.8700717 0.3970785 0.2920686 -0.6627289 0.669473 0.3355538 -0.811684 0.2728294 0.5164622 -0.8097091 0.2871783 0.5117616 -0.5968434 0.6470812 0.4744092 -0.6549973 0.4336941 0.6187794 -0.8450359 0.3596085 -0.3957225 -0.8644374 0.3379769 -0.3721823 -0.6214241 0.716521 -0.3169067 -0.9340639 0.3260318 -0.1456984 -0.344168 0.9343436 -0.09246778 -0.6194387 0.7620226 -0.1887257 -0.9122951 0.4095319 -0.001158416 -0.3308489 0.9433752 -0.0241329 -0.6903853 0.7229554 -0.0265271 -0.9137166 0.3623613 0.1838923 -0.6165874 0.7648397 0.1866559 -0.9405468 -0.3021882 -0.1550943 -0.9214342 -0.388508 0.004546046 -0.7476671 -0.535717 0.39243 -0.925163 -0.3407908 0.1671379 -0.6387545 -0.1227549 0.7595551 -0.7298255 -0.3640063 0.5786659 -0.7291942 -0.3638407 0.5795652 -0.9481199 -0.2106047 0.2381477 -0.8642783 -0.1702699 0.4733195 -0.3691449 -0.9253733 -0.08611851 -0.3545416 -0.9350402 -3.75552e-4 -0.6411742 -0.7006815 -0.3129556 -0.639632 -0.7485261 -0.1748704 -0.4883298 -0.8490272 0.2017103 -0.8575857 -0.3406808 -0.3853356 -0.6343935 -0.7468386 0.1994416 -0.7080169 -0.7060084 -0.01625216 -0.8699679 -0.3266091 -0.3694352 -0.6840071 -0.634144 0.3605493 0.5744258 -0.0131905 -0.8184505 0.5734965 -0.01344007 -0.8190979 0.5735707 -0.01295322 -0.8190537 0.5733633 -0.01297271 -0.8191986 0.5737519 -0.01362019 -0.818916 0.5736683 -0.01303118 -0.818984 0.5735567 -0.01313436 -0.8190606 0.5732385 -0.01300871 -0.8192853 0.5735883 -0.01333022 -0.8190354 0.5734995 -0.01301258 -0.8191025 0.5735993 -0.01303887 -0.8190323 0.5735424 -0.01293176 -0.8190739 0.5735044 -0.01310157 -0.8190978 0.5735027 -0.01319354 -0.8190975 0.5738461 -0.01263076 -0.8188658 0.5734899 -0.01278966 -0.819113 0.5733531 -0.01287639 -0.8192073 0.573814 -0.01241225 -0.8188916 -0.5726945 0.01362544 0.8196557 -0.5732784 0.01317793 0.8192548 -0.5735483 0.01267504 0.8190737 -0.5734533 0.01290357 0.8191367 -0.5727927 0.01356494 0.819588 -0.5729836 0.01295596 0.8194645 -0.5734569 0.0133329 0.8191273 -0.5734356 0.01399284 0.8191312 -0.5739353 0.01269954 0.8188023 -0.5733094 0.01294851 0.8192367 -0.5735425 0.01302129 0.8190723 -0.5736233 0.01273339 0.8190203 -0.5722342 0.0119304 0.8200035 -0.573372 0.01279383 0.8191954 -0.5725318 0.01223731 0.8197913 -0.5736985 0.01322275 0.8189599 -0.5732708 0.01267439 0.8192679 -0.5735172 0.013143 0.8190882 0.734335 0.678604 0.01577317 0.6807032 0.7097403 -0.1814169 -0.614286 0.6837347 -0.393903 0.6607547 0.6771128 -0.3239158 0.5217851 0.709623 -0.4734717 -0.6679067 0.7265948 -0.161123 0.4377631 0.6779402 -0.5905596 -0.7173401 0.6962561 -0.02551048 0.2454534 0.711695 -0.658212 -0.6629422 0.7288385 0.1711785 0.1164819 0.6809567 -0.7230008 -0.6437749 0.6977569 0.3141484 -0.1160411 0.7181962 -0.6860968 -0.5040037 0.7289978 0.4631873 -0.2581201 0.6765411 -0.6896856 -0.4031397 0.6887713 0.6025552 -0.4969093 0.7276791 -0.4728258 -0.1934233 0.7390142 0.6453259 0.04211151 0.6767973 0.734964 0.2402873 0.7250522 0.6454157 0.4038464 0.6869001 0.6042156 0.5356146 0.7160254 0.4476883 0.6416265 0.6821265 0.3507404 0.6857196 0.7120356 0.1509766 0.5734556 -0.01304191 -0.8191329 0.573495 -0.01273238 -0.8191102 0.4676342 6.1276e-4 0.8839219 0.485167 0.3285198 0.8103627 0.627514 -0.2062745 0.7507843 0.6870756 0.1893847 0.7014704 0.7827461 -0.1808524 0.595484 0.8289147 0.1691701 0.5331812 0.8922124 -0.2010475 0.4043971 0.9221392 0.1943822 0.334477 0.9247989 -0.3370113 0.1765517 0.9905269 -0.01137393 0.1368472 -0.5734555 0.01298052 0.8191339 -0.5735146 0.01304388 0.8190916 -0.9773005 0.01044249 -0.2116002 -0.9220248 -0.3104368 -0.2312991 -0.8814479 0.1457316 -0.4492352 -0.8736433 -0.1081932 -0.4743854 -0.7434113 0.1199927 -0.6579829 -0.7249453 -0.1337606 -0.6756941 -0.5296158 0.3208443 -0.7852173 -0.53314 5.93807e-4 -0.8460269 0.57349 -0.01303309 -0.8191089 0.5734641 -0.01304179 -0.819127 0.9774965 -0.0104466 0.2106927 0.9140695 -0.3305317 0.2350017 0.8850326 0.1301515 0.4469653 0.8708999 -0.1233199 0.475737 0.7460509 0.1113798 0.6565079 0.7212834 -0.1423118 0.6778627 0.5367166 0.3194153 0.7809669 0.5323216 -4.94504e-4 0.8465421 -0.5735271 0.01304197 0.8190829 -0.5735024 0.01243209 0.8191096 -0.4674344 -5.64084e-4 -0.8840276 -0.4772177 0.3276749 -0.8154094 -0.6326285 -0.2010173 -0.7479126 -0.6822857 0.1961484 -0.7042812 -0.7871091 -0.169987 -0.592928 -0.8245719 0.1818557 -0.5357329 -0.8969509 -0.184772 -0.4016696 -0.9171943 0.2117789 -0.3374974 -0.9328995 -0.3164487 -0.1719264 -0.9905169 0.01085478 -0.1369621 -0.5793907 0.01299154 0.8149465 -0.6089327 0.1811575 0.7722583 0.8041565 -0.04737305 0.5925269 0.8334634 0.1865924 0.5201175 0.9637176 -0.2590273 -0.06444662 0.9298841 0.2178372 -0.2964165 0.6052262 -0.1808419 -0.7752403 0.5149567 0.09594064 -0.8518304 -0.1430254 -0.1491371 -0.9784181 -0.2236188 0.03067833 -0.9741938 -0.8118119 0.1086859 -0.573715 -0.8472008 -0.1340612 -0.5140801 -0.5902867 -0.02312988 0.8068624 -0.5550456 0.04583883 0.830556 0.680785 0.01785254 0.7322657 0.6551501 -0.03774869 0.7545551 -0.4615806 -0.01497095 0.886972 -0.4621646 -0.01331633 0.8866943 -0.9421971 0.1264424 0.3102854 -0.9867815 -0.1378405 0.08521872 -0.801977 0.1278466 -0.5835136 -0.7699603 -0.03114134 -0.6373316 0.5808943 -0.02057057 -0.8137191 0.5840441 -0.0131095 -0.8116161 0.8190974 -0.00601828 0.573623 0.8191016 -0.006069302 0.5736165 -0.8190854 0.005895972 -0.5736415 -0.8190936 0.006245076 -0.573626 0.1651293 -0.009109914 -0.98623 0.1651671 -0.009156227 -0.9862231 -0.5735301 0.01303863 0.8190808 -0.5734792 0.01306402 0.8191161 -0.8190379 0.006024599 -0.5737079 -0.8190191 0.005902349 -0.5737359 0.5735068 -0.0130977 -0.8190962 0.5735098 -0.01294618 -0.8190965 0.8190168 -0.006028234 0.5737379 0.8190569 -0.006023645 0.5736806 -0.1651165 0.009162187 0.9862316 -0.1649937 0.008814156 0.9862552 0.5734462 -0.01276814 -0.8191438 0.5734858 -0.01276385 -0.8191161 0.8190788 -0.006277322 0.5736468 0.8190113 -0.006044805 0.5737456 -0.5735005 0.0129463 0.819103 -0.5735365 0.01292264 0.8190782 0.4308214 0.5057337 -0.747413 0.5735111 -0.01308727 -0.8190934 0.819065 -0.005800962 0.5736716 0.8191156 -0.006024897 0.5735968 -0.5734628 0.01308667 0.8191272 -0.5734871 0.01293081 0.8191126 -0.8190215 0.005941689 -0.5737323 -0.819059 0.006010413 -0.5736779 0.5734923 -0.01271539 -0.8191123 0.5734869 -0.01286268 -0.8191139 -0.8192517 0.005935311 -0.5734033 -0.8190982 0.005770027 -0.5736243 0.573458 -0.01278948 -0.8191351 0.5735853 -0.01298993 -0.8190429 0.8191224 -0.005656242 0.573591 0.8191482 -0.006076276 0.57355 -0.7199358 0.01348298 0.6939097 -0.5453488 0.3021653 0.7818509 -0.8191905 0.005915224 -0.573491 -0.8191112 0.00597769 -0.5736036 -0.5734665 0.01304858 0.8191252 -0.5735089 0.01309186 0.8190948 -0.8190548 0.006182789 -0.5736821 -0.8192264 0.005887866 -0.5734402 0.1236463 -0.007131099 -0.9923008 0.124083 -0.008641958 -0.9922343 -0.5854396 0.01432943 0.8105895 -0.5850126 0.01310443 0.8109183 -0.8275193 0.0352801 -0.5603278 -0.819154 0.005926072 -0.5735431 0.5884411 0.2687507 -0.7625682 0.5735155 -0.0129224 -0.8190928 -0.9833369 -0.05513554 0.1732306 -0.9936161 0.0311709 0.1084235 -0.5124067 -0.1005056 0.8528413 -0.607138 0.07690751 0.7908658 0.1448828 0.1455852 0.9786797 0.3602545 -0.1419496 0.9219909 0.8153057 0.02236229 0.5785989 0.8107555 -0.005715131 0.585357 -0.08050638 0.008181571 0.9967206 -0.0790795 0.01247173 0.9967904 -0.8191206 0.006116807 -0.5735889 -0.8191127 0.005947887 -0.5736019 0.2987166 -0.01064985 -0.9542825 -0.589734 0.434062 -0.6810316 -0.8190308 0.006048917 -0.5737178 -0.7889037 0.01417094 0.6143535 -0.7889762 0.01415497 0.6142608 -0.8320336 0.006324648 -0.5546891 -0.817584 0.05468559 -0.5732067 0.8254004 -0.01428347 -0.5643671 0.7660999 0.2868662 -0.5751513 0.8191927 -0.006092786 0.5734862 0.8190906 -0.005533993 0.5736376 -0.2203797 0.3017153 0.9275779 -0.2769321 0.01029533 0.9608345 -0.6093163 -0.4321119 -0.6648406 -0.818269 0.03989827 -0.5734493 0.5735102 -0.01309823 -0.8190937 0.5734846 -0.01301234 -0.819113 -0.8191248 0.006001055 -0.5735841 -0.8191694 0.006068348 -0.5735197 -0.5734801 0.01309788 0.8191149 -0.57349 0.01302832 0.819109 -0.8191348 0.006269633 -0.5735669 -0.8190687 0.006056189 -0.5736637 0.5735082 -0.01273173 -0.8191009 0.5734285 -0.01298832 -0.8191528 0.8191576 -0.006054818 0.5735365 0.8191534 -0.006052851 0.5735427 -0.5734911 0.01298743 0.8191089 -0.5735901 0.01306712 0.8190383 0.8191307 -0.005950212 0.5735761 0.8191505 -0.00608772 0.5735463 0.5735255 -0.01296961 -0.8190851 0.5735668 -0.01300066 -0.8190556 0.8191339 -0.006054818 0.5735704 0.8191419 -0.006136834 0.5735582 -0.5357536 0.01269483 0.844279 -0.5458341 0.2994652 0.7825508 -0.8055683 0.00571686 -0.5924753 -0.8176252 0.05481714 -0.5731354 -0.8601935 -0.001255035 -0.5099664 -0.04146957 0.02052336 0.998929 -0.01380461 0.07410454 0.997155 -0.8670341 -0.06985455 0.4933277 -0.9022737 0.09878379 0.4196953 0.8450409 -0.07897561 0.5288373 0.8820852 0.08391052 0.463557 0.7521136 -0.1055025 -0.650534 0.7053867 0.0589295 -0.7063688 -0.1587057 -0.06145328 -0.9854117 -0.2221971 0.04071265 -0.9741514 -0.8475011 -0.04329365 -0.5290252 -0.1173975 -0.9892978 -0.08664774 -0.4201834 -0.8608666 -0.2869752 -0.4725015 -0.8264263 -0.3062058 -0.5789291 -0.7049608 -0.4097213 -0.3070716 -0.9359414 -0.1723971 -0.7285209 -0.4652281 -0.5028122 -0.4575329 -0.822409 -0.3380936 -0.5902373 -0.7081756 -0.3874368 -0.7347369 -0.453877 -0.5041404 -0.8097312 -0.1508006 -0.5670933 -0.7451626 -0.4151579 -0.5218972 -0.7807018 -0.3266937 -0.5327062 -0.8036765 -0.2028071 -0.5594401 -0.8105213 -0.1466649 -0.5670491 0.3810788 -0.003665566 -0.9245354 0.3404101 -0.01873254 -0.9400905 -0.963559 0.01767963 -0.2669111 -0.1287111 0.003440678 -0.9916763 -0.9744636 0.002569139 -0.2245311 -0.1819987 -0.01982253 -0.9830991 -0.9771599 0.02126932 0.2114387 -0.6962468 0.01797389 -0.7175775 -0.9672245 0.00597006 0.2538529 -0.7334465 -0.004894196 -0.6797296 -0.766864 0.02174359 0.6414412 -0.7384768 0.006141245 0.6742509 -0.3808132 0.01894754 0.9244579 -0.2959844 -0.0141099 0.9550886 0.1294007 0.04160964 0.990719 0.3330433 -0.03395384 0.9423001 0.7230283 0.02551019 0.6903473 0.7583468 0.001329004 0.65185 0.9988262 0.03080695 0.03738093 0.9738868 -0.03131014 0.2248649 0.9662966 -0.04514437 -0.2534421 0.7961334 0.01008802 -0.6050371 0.7382555 -0.02179867 -0.674169 -0.1778168 0.9802933 -0.08606046 0.04106217 0.9981693 -0.04440671 -0.8419523 -0.07482546 -0.5343382 -0.5339458 0.7775374 -0.3321713 -0.3471025 0.8847957 -0.3108962 -0.6934244 -0.530347 -0.4877446 -0.7473478 -0.3443849 -0.5682168 -0.7736445 0.3967369 -0.4940385 -0.6826823 -0.5420631 -0.4900128 -0.6431559 0.5683155 -0.513194 -0.4280194 -0.8631663 -0.2678495 -0.786007 0.1216406 -0.6061326 -0.3567457 -0.8939894 -0.2711375 -0.06972712 -0.9973479 0.02086609 -0.1796167 -0.9698163 -0.1649067 0.2990073 -0.9181769 0.2598958 0.2125512 -0.9709106 0.1102481 0.5540734 -0.7437719 0.3739067 0.5800185 -0.7258026 0.3698503 0.6923364 -0.5746073 0.4364596 0.720474 -0.4259748 0.5472319 0.8249737 -0.1134932 0.5536587 0.8174161 -0.1286606 0.5614957 0.7711126 0.2807428 0.571462 0.8498775 0.08226227 0.52052 0.6869785 0.5736179 0.44612 0.6859908 0.5828282 0.4355778 0.4253169 0.8464108 0.3204597 0.5754104 0.7453644 0.3366524 0.2095084 0.9720916 0.1055664 0.1987574 0.9770969 0.07600897 0.365754 0.8811886 0.2995506 0.2814059 0.9484222 0.1459658 -0.8195678 -0.07303869 -0.568308 0.05579459 0.9984374 0.003159165 -0.8114091 -0.04274243 -0.5829137 -0.01060622 0.9999407 0.002517521 -0.7754855 -0.3586374 -0.5196169 -0.2160233 0.969462 -0.1160922 -0.7755684 -0.3612145 -0.5177045 -0.3150933 0.9040478 -0.2888148 -0.5583024 -0.7470062 -0.3609435 -0.5613909 0.7494415 -0.3509669 -0.5670514 -0.7178764 -0.403864 -0.6138755 0.6298742 -0.4758313 -0.7712539 0.3563607 -0.5274227 -0.7773694 0.347977 -0.5240314 -0.2427783 -0.9583371 -0.1504957 -0.2572501 -0.9493177 -0.1806058 -0.01197695 -0.9996129 0.02510952 -0.01065069 -0.9995537 0.02790844 0.3484956 -0.9065506 0.2381531 0.3493376 -0.9055522 0.2407043 0.5162559 -0.7442846 0.4236983 0.6726644 -0.6046133 0.4265741 0.7299346 -0.4028264 0.5522016 0.8247495 -0.1979476 0.5297219 0.8006641 0.09950071 0.5907933 0.7842509 0.1282506 0.607044 0.7429872 0.3523468 0.5690534 0.7288422 0.5013168 0.4663373 0.5052221 0.7702065 0.389272 0.5320869 0.7533827 0.3863912 0.01238989 0.9998976 -0.007163226 0.01234406 0.9998982 -0.007173538 0.01234591 0.9998985 -0.007123887 0.01234191 0.9998983 -0.007156491 0.0123676 0.9998981 -0.007146477 0.01236701 0.9998981 -0.007129967 0.0106244 0.9999252 -0.006071805 0.0123685 0.9998981 -0.007134497 0.01092982 0.9998969 -0.009316027 0.01410782 0.9998669 -0.008207142 0.0138024 0.9998925 -0.004960656 0.01236253 0.9998982 -0.00713706 0.0123676 0.9998981 -0.007137417 0.01236754 0.999898 -0.00714606 0.01238954 0.999898 -0.007112205 0.01238632 0.9998977 -0.0071581 0.01238238 0.9998981 -0.007109463 0.01234561 0.9998986 -0.007105588 0.01212888 0.9999018 -0.007027208 0.01242935 0.9998969 -0.007194995 0.01256787 0.9998955 -0.007152974 0.01242154 0.9998968 -0.007215201 0.01255404 0.9998952 -0.007228553 0.01227009 0.9999009 -0.006903946 0.01233607 0.9998979 -0.007215678 0.01239657 0.999898 -0.007104158 0.01228773 0.9998984 -0.007231831 0.01209676 0.9999008 -0.007222652 0.01241385 0.9998975 -0.007143259 0.01237738 0.9998978 -0.00717014 0.01237821 0.9998981 -0.007118523 0.01236379 0.9998982 -0.007122457 0.01235496 0.9998984 -0.007114768 0.012371 0.9998978 -0.007162034 0.01236808 0.9998981 -0.00714159 0.01235741 0.9998986 -0.007087945 0.01235884 0.9998984 -0.007105529 0.01236826 0.999898 -0.007161259 0.01237607 0.999898 -0.007142663 0.01238566 0.9998981 -0.007095932 0.01237142 0.9998981 -0.00713694 0.01237046 0.999898 -0.007143199 0.01236629 0.9998978 -0.007177054 0.01236975 0.9998981 -0.007132589 0.01235932 0.9998986 -0.007080972 0.01240259 0.9998976 -0.007146894 0.01228737 0.999899 -0.00714147 0.01235705 0.9998981 -0.007154285 0.01235449 0.9998983 -0.007141411 0.01232933 0.9998987 -0.007131338 0.0124042 0.999897 -0.007220685 0.01237308 0.9998979 -0.007145464 0.01236063 0.9998974 -0.007234334 0.01237201 0.9998978 -0.007162809 0.01236975 0.9998976 -0.007204651 0.01236814 0.9998981 -0.007127404 0.01232081 0.9998986 -0.007157266 0.0123943 0.9998977 -0.007136702 0.01234537 0.9998984 -0.007138073 0.01234227 0.9998978 -0.007217168 0.01235389 0.9998978 -0.007196784 0.01234745 0.9998984 -0.007122933 0.01238268 0.9998978 -0.007145941 0.0123409 0.9998981 -0.007169127 0.01236075 0.9998982 -0.007139503 0.01237517 0.9998975 -0.007205426 0.01236486 0.9998981 -0.00713098 0.01238059 0.9998982 -0.007102489 0.01236963 0.999898 -0.007140934 0.01237994 0.999898 -0.007127702 0.01235932 0.9998983 -0.007122457 0.012349 0.9998984 -0.007135331 0.0123648 0.999898 -0.007147192 0.01236051 0.9998984 -0.007104098 0.01235395 0.9998984 -0.007126092 0.01238995 0.9998975 -0.007175683 0.01237452 0.9998978 -0.007163286 0.01236313 0.9998983 -0.007122457 0.01237136 0.9998982 -0.007120013 0.01236462 0.999898 -0.007168591 0.01235574 0.9998987 -0.007074594 0.01238441 0.9998979 -0.007128536 0.01238024 0.999898 -0.007131397 0.01235002 0.9998986 -0.007089853 0.01240915 0.9998974 -0.007164835 0.01247692 0.9998965 -0.007169902 0.01246327 0.9998975 -0.007063448 0.01238155 0.999898 -0.007130622 0.012443 0.9998963 -0.007250726 0.0123676 0.9998981 -0.007124662 0.01238054 0.9998993 -0.00694549 0.01237529 0.9998984 -0.007075011 0.5735041 -0.01300251 -0.8190995 0.5734926 -0.01295447 -0.8191084 0.5735157 -0.01288777 -0.8190932 0.5734955 -0.01294636 -0.8191064 0.5735046 -0.01294934 -0.8190999 0.5734935 -0.01290887 -0.8191084 0.5735033 -0.0129354 -0.8191012 0.5735026 -0.01294851 -0.8191015 0.5734926 -0.0129947 -0.8191078 0.573495 -0.01293349 -0.819107 0.5736018 -0.0129472 -0.819032 0.5735491 -0.01292359 -0.8190693 0.5741418 -0.01424646 -0.8186321 0.5735485 -0.01302558 -0.8190681 0.5734136 -0.01294976 -0.8191637 0.5743036 -0.01390415 -0.8185244 0.5734959 -0.01294058 -0.8191063 0.5734881 -0.01293617 -0.8191118 0.5735166 -0.01293003 -0.8190919 0.5735335 -0.01293361 -0.8190801 0.5735037 -0.01291602 -0.8191012 0.5733845 -0.01291072 -0.8191847 0.5734581 -0.01290214 -0.8191333 0.5735313 -0.01299494 -0.8190806 0.5734925 -0.01299899 -0.8191077 0.5735043 -0.01292651 -0.8191006 0.5746058 -0.01351857 -0.8183188 0.5735167 -0.01291948 -0.819092 0.5735334 -0.01290023 -0.8190806 0.5734705 -0.0129441 -0.8191239 0.5734885 -0.01293474 -0.8191115 0.5668042 -0.0575937 -0.821837 0.5735043 -0.01296031 -0.8191 0.5734941 -0.0130074 -0.8191064 0.5734804 -0.0129106 -0.8191176 0.5734782 -0.0129351 -0.8191187 0.5734931 -0.01291131 -0.8191087 0.5735201 -0.01290118 -0.81909 0.5734902 -0.01292693 -0.8191105 0.5735529 -0.01284611 -0.8190678 0.5735189 -0.01290625 -0.8190907 0.5734678 -0.01299911 -0.819125 0.5734729 -0.01301211 -0.8191214 0.5734936 -0.01298373 -0.8191071 0.5734862 -0.012829 -0.8191148 0.5734717 -0.01304912 -0.8191215 0.5734862 -0.01293802 -0.8191131 0.5734861 -0.0129531 -0.819113 0.5734857 -0.01300162 -0.8191124 0.5735053 -0.01287555 -0.8191007 0.5735034 -0.01293605 -0.8191011 0.5735136 -0.01293683 -0.819094 0.5735099 -0.01293754 -0.8190966 0.5734929 -0.01288652 -0.8191093 0.5734791 -0.01295208 -0.8191179 0.573497 -0.01294076 -0.8191055 0.573499 -0.01293009 -0.8191044 0.5734791 -0.01292294 -0.8191183 0.5734853 -0.01297271 -0.8191131 0.5735171 -0.01292532 -0.8190916 0.5735272 -0.01295119 -0.8190842 0.5734991 -0.01293087 -0.8191041 -0.5791563 -0.03454673 0.8144842 -0.570969 0.01155656 0.8208903 -0.5712756 0.01107901 0.8206835 -0.5721154 0.009987175 0.8201123 -0.5735303 0.0129705 0.8190817 -0.5734795 0.01295036 0.8191176 -0.5734962 0.01294267 0.819106 -0.5734942 0.01293706 0.8191075 -0.5734961 0.01295709 0.8191059 -0.5734714 0.01294845 0.8191233 -0.5735254 0.01294547 0.8190856 -0.5734924 0.01293277 0.8191089 -0.5734856 0.01295655 0.8191132 -0.5734666 0.01295 0.8191266 -0.5735103 0.01293838 0.8190963 -0.5734953 0.01298105 0.819106 -0.5734756 0.01293772 0.8191205 -0.573511 0.01295381 0.8190954 -0.5735077 0.01290994 0.8190986 -0.5735029 0.0129348 0.8191015 -0.5734977 0.01294207 0.819105 -0.5734956 0.0129466 0.8191064 -0.5735082 0.01295948 0.8190973 -0.5735155 0.01293796 0.8190926 -0.5734755 0.01294624 0.8191204 -0.573508 0.01294392 0.8190978 -0.57352 0.01300972 0.8190884 -0.5735098 0.01294547 0.8190964 -0.5735 0.01288425 0.8191043 -0.5734974 0.0129407 0.8191052 -0.5734894 0.01293891 0.8191107 -0.5735768 0.0129798 0.8190491 -0.5734766 0.01298671 0.8191191 -0.5735566 0.01293283 0.8190639 -0.5734928 0.01298582 0.8191077 -0.5733547 0.01292383 0.8192055 -0.5733488 0.01300394 0.8192083 -0.5735483 0.0127449 0.8190727 -0.5734878 0.01294589 0.8191119 -0.5734593 0.01295655 0.8191317 -0.5735562 0.01282405 0.8190659 -0.573441 0.01290416 0.8191454 -0.5734834 0.01294595 0.8191148 -0.5735065 0.01294386 0.8190987 -0.5734474 0.0130639 0.8191383 -0.5735363 0.01295006 0.8190778 -0.5734477 0.012928 0.8191403 -0.5734639 0.01292949 0.8191289 -0.5734736 0.01294612 0.8191218 -0.5734767 0.01294225 0.8191197 -0.5735388 0.01298028 0.8190755 -0.5734265 0.01292365 0.8191551 -0.5734977 0.0129128 0.8191055 -0.5734995 0.01297581 0.8191031 -0.5734952 0.01296979 0.8191064 -0.5735154 0.0129565 0.8190923 -0.5735105 0.01295542 0.8190959 -0.5734833 0.01292496 0.8191154 -0.5735064 0.01295518 0.8190986 -0.5735257 0.01288229 0.8190863 -0.5734784 0.01294904 0.8191183 -0.5735058 0.01291805 0.8190998 -0.5734778 0.0129804 0.8191183 -0.5735136 0.01294863 0.8190938 -0.5734797 0.01291245 0.8191182 -0.7703348 0.005316615 -0.6376175 0.9125103 -0.01649212 0.4087212 0.902178 0.009648263 0.431256 -0.7240236 -0.05894643 -0.687252 0.4947147 0.08995461 -0.8643875 0.6131479 -0.06459259 -0.787323 -0.5734511 0.008516669 0.8191955 -0.5709762 0.01258665 0.8208702 0.3115308 -0.01071166 -0.9501758 0.3123777 -0.009134531 -0.9499141 0.8191254 -0.005895912 0.5735843 0.8191478 -0.006135106 0.5735498 -0.7785279 0.01132935 0.6275078 -0.7794067 0.01413106 0.626359 0.8346794 -0.2186309 0.505481 0.9493957 0.08287626 0.3029514 0.1926734 0.1458191 -0.9703679 0.8804076 0.126946 -0.4569104 -0.2535669 -0.1786436 -0.9506789 0.7227087 -0.2047578 -0.6601261 -0.6869328 0.2366517 -0.6871094 -0.9944953 0.09293311 0.0483992 -0.9360267 -0.1384206 -0.3235642 -0.8235422 -0.1456736 0.5482314 -0.5276817 0.1969693 0.82629 -0.1274605 -0.1622695 0.9784798 0.3860983 0.180416 0.9046427 0.08245795 -0.9940686 0.07091087 0.09138119 -0.9931964 0.07218319 0.3580978 -0.8922586 0.2750284 0.3967551 -0.8737313 0.2813876 0.642351 -0.6055257 0.4698126 0.6687247 -0.5770584 0.4688399 0.7412552 0.3895118 0.5466455 0.8261554 0.2653333 0.497057 0.7963508 -0.2181929 0.5641074 0.7814081 -0.1766368 0.5984988 0.7854197 -0.01760423 0.6187132 0.820672 -0.03743606 0.5701718 0.5362044 -0.7370423 0.4114044 0.5781598 -0.7093527 0.4031749 -0.005224645 -0.9999818 0.003033041 0.004559099 -0.999989 0.001109182 -0.3832412 -0.8956298 -0.2257731 -0.4318365 -0.8437883 -0.3186513 -0.7185472 -0.4881185 -0.4954093 -0.7239658 -0.4852458 -0.4903163 -0.8170984 -0.08081656 -0.5708056 -0.7871717 -0.2856408 -0.5465986 -0.7871337 -0.2856597 -0.5466436 -0.8171031 -0.08080911 -0.5707999 -0.8187862 0.02353477 -0.5736161 -0.8187426 0.02351814 -0.5736789 -0.8187719 0.0234937 -0.5736381 -0.8187901 0.02339982 -0.573616 -0.818771 0.02345901 -0.5736408 -0.8187702 0.02340543 -0.5736441 -0.8187752 0.02348142 -0.5736339 -0.8187856 0.02346968 -0.5736196 -0.8187862 0.02348661 -0.5736179 -0.818781 0.02348709 -0.5736256 0.4770708 -0.5111814 -0.7149106 0.5417809 -0.3234848 -0.7757778 0.4562783 -0.5846638 -0.6708044 0.2773702 -0.8557623 -0.4367344 0.2657881 -0.8720963 -0.4108587 0.8187707 -0.02350407 0.5736393 0.8187638 -0.02351766 0.5736488 0.8139026 -0.0157482 0.5807878 0.8187791 -0.02348953 0.5736279 0.8187499 -0.02348709 0.57367 0.8187528 -0.02342289 0.5736683 0.818799 -0.02350866 0.5735988 0.81879 -0.02348357 0.5736128 0.8187618 -0.02348023 0.573653 0.8187614 -0.02345532 0.5736547 0.8138996 -0.01518267 0.5808073 0.818778 -0.02349042 0.5736294 0.8187743 -0.02354228 0.5736327 0.8187773 -0.02342873 0.5736332 0.8187791 -0.0234586 0.5736294 0.8187741 -0.0234822 0.5736356 0.8187637 -0.02345776 0.5736513 0.01005125 0.9995965 0.02656745 0.1067919 0.9925249 0.05907392 0.1182175 0.9929854 -0.002157688 0.263198 0.9497769 0.1692657 0.2631919 0.9497801 0.1692574 0.540033 0.7578216 0.3661567 0.4094619 0.8705369 0.2729591 0.409475 0.87054 0.2729297 0.5624123 0.7493306 0.3495657 0.5933014 0.6683274 0.4487003 0.689915 0.5950749 0.4121932 0.7276268 0.4015017 0.5561976 0.8022629 0.1031862 0.5879854 0.8350865 0.1776594 0.5206416 0.7379946 -0.3392286 0.5833421 0.8002223 -0.2677695 0.5366041 0.7008485 -0.5628619 0.4381757 0.4997236 -0.734961 0.4583762 0.4690214 -0.8386827 0.2768219 0.1854817 -0.966418 0.1778561 0.1718438 -0.9681794 0.1819297 -0.1490984 -0.9848237 -0.0888372 -0.1166897 -0.9887124 -0.09397524 -0.3905989 -0.8880311 -0.242556 -0.3703373 -0.8959703 -0.2451276 -0.5748828 -0.7074824 -0.4110699 -0.5763053 -0.7070638 -0.4097963 -0.2345789 -0.9573137 -0.1688886 -0.4172213 -0.8650929 -0.2784612 -0.2546288 -0.9531618 -0.1632384 -0.4362149 -0.8577363 -0.2720388 -0.03153604 -0.9993966 -0.01456475 -0.05669558 -0.9983817 -0.004426836 0.5541226 -0.7275832 0.4044389 0.5512516 -0.7300504 0.403916 0.796142 -0.0624122 0.6018826 0.8008903 -0.2435259 0.5470558 0.7775328 0.3845935 0.4975243 0.5343378 0.742995 0.4030405 0.4716061 0.8266144 0.3070772 0.4399242 0.8469503 0.2985666 0.4404535 0.8479242 0.2950004 0.291103 0.9378345 0.1890122 0.2910979 0.9378352 0.1890161 0.1254462 0.98947 0.07219696 0.125445 0.9894694 0.0722084 -0.04135316 0.9983627 -0.03952091 -0.04097628 0.9981703 -0.04446339 -0.7051491 0.5213673 -0.4805632 -0.1316842 0.9848492 -0.1128339 -0.1254421 0.9857942 -0.1116878 -0.725556 0.3984099 -0.5611043 -0.8019218 -0.2886949 -0.5230455 -0.7283132 -0.4384368 -0.5266243 -0.4580868 -0.840048 -0.2906478 -0.2848266 -0.9406462 -0.1845496 -0.4449704 -0.8444411 -0.2981957 -0.114353 -0.9913493 -0.06442064 -0.2847955 -0.9406539 -0.1845589 -0.1143638 -0.9913489 -0.06440836 0.06082713 -0.9961597 0.06297457 0.06116354 -0.996408 0.05856764 0.08243978 -0.9940696 0.07091856 0.09136104 -0.9931987 0.07217746 0.358112 -0.8922572 0.2750146 0.396708 -0.8737628 0.2813565 0.6423822 -0.6054729 0.4698381 0.6687007 -0.5771012 0.4688216 -0.03153699 -0.9993966 -0.0145654 -0.0566864 -0.9983822 -0.004430592 -0.2345791 -0.9573138 -0.1688873 -0.4194982 -0.8634676 -0.2800801 -0.2546244 -0.9531658 -0.1632228 -0.4274949 -0.8604919 -0.2771314 -0.5924584 -0.7070203 -0.3861548 -0.5917834 -0.7066828 -0.3878042 0.6899271 0.5950195 0.412253 0.7302141 0.3523022 0.5853807 0.8502818 0.176935 0.4956966 0.7684078 -0.09826737 0.632371 0.6704673 -0.4934156 0.5540891 0.8208652 -0.3045314 0.4831574 0.5674561 -0.7441372 0.352496 0.5659173 -0.7345995 0.3743011 0.2197687 -0.9544826 0.2016549 0.2162353 -0.9671086 0.133953 -0.1429038 -0.9881207 -0.05653393 -0.3703509 -0.8959612 -0.2451404 -0.1491147 -0.9848212 -0.0888381 -0.3747438 -0.8883711 -0.2652621 0.5933156 0.6682949 0.4487302 0.1067818 0.9925259 0.05907768 0.1182163 0.9929856 -0.002150237 0.2631949 0.9497824 0.1692394 0.263189 0.9497774 0.1692768 0.540015 0.7578479 0.3661291 0.4094783 0.8705294 0.272958 0.4094992 0.8705353 0.2729083 0.5624769 0.7493065 0.3495133 0.01005071 0.9995966 0.02656692 -0.5089862 -0.4764719 0.7168735 -0.5022682 -0.5212975 0.6899098 -0.3253366 -0.839254 0.4356706 -0.309338 -0.8638043 0.3976836 -0.8187701 0.02345502 -0.5736424 -0.8187803 0.02350383 -0.5736259 -0.8187465 0.0235123 -0.5736736 -0.818742 0.02351993 -0.5736796 -0.8187705 0.02351933 -0.5736392 -0.8187624 0.02345967 -0.5736531 -0.8187828 0.02349156 -0.5736227 -0.8187801 0.0234878 -0.5736266 -0.8187693 0.02348363 -0.5736423 -0.7247657 -0.4852166 -0.4891623 -0.7213495 -0.4818499 -0.4974691 -0.817097 -0.0808143 -0.5708078 -0.7871612 -0.2856339 -0.5466173 -0.7871435 -0.2856543 -0.5466322 -0.8170893 -0.08080887 -0.5708197 -0.4528031 -0.8435583 -0.2887538 -0.4718194 -0.8181782 -0.3285895 -0.0255534 -0.9996283 0.009513795 -0.03138864 -0.99933 -0.01882481 0.6919896 -0.5203864 0.5003485 0.6862542 -0.5476637 0.4786646 0.408666 -0.8584423 0.3099504 0.3884567 -0.8802981 0.2723541 0.8167686 -0.02066552 0.5765953 0.7990985 -0.02987337 0.6004576 0.7421855 0.3895461 0.5453572 0.8252936 0.2736589 0.4939649 0.7963618 -0.2181569 0.564106 0.7814067 -0.1766292 0.5985029 0.5685831 -0.6976576 0.4358753 0.7052615 -0.5448557 0.4535841 0.7944427 -0.04145908 0.6059225 0.7992588 0.3278892 0.5036608 0.5819684 0.6764669 0.4513374 0.4142482 0.8802159 0.2315568 0.06115937 -0.9964082 0.05857026 0.08202183 -0.9954206 0.04909533 -0.4484496 -0.8417191 -0.3006691 -0.4495393 -0.8432358 -0.2947337 -0.2848086 -0.9406473 -0.184572 -0.2848085 -0.9406538 -0.1845394 -0.1143648 -0.9913485 -0.0644136 -0.114366 -0.9913474 -0.06442737 -0.705263 0.5209981 -0.4807963 -0.1319956 0.984804 -0.1128644 -0.1254161 0.9858001 -0.1116647 -0.7256482 0.3981067 -0.5612004 -0.8005236 -0.2964536 -0.5208429 -0.7329217 -0.4320263 -0.5255275 0.4399389 0.8469433 0.2985649 0.4404616 0.8479259 0.2949835 0.2911034 0.9378359 0.1890048 0.2911037 0.9378388 0.1889899 -0.03641033 0.9984843 -0.04127317 0.1254482 0.9894708 0.07218271 0.1254448 0.9894698 0.0722019 -0.05074566 0.9981145 -0.03452938 0.01226025 0.9998992 -0.007177889 0.01239013 0.9998977 -0.007155656 0.01236206 0.9998984 -0.007094085 0.01240688 0.999898 -0.007081925 0.01233226 0.9998986 -0.007117033 0.01235455 0.9998981 -0.007159233 0.01238328 0.9998983 -0.007088899 0.01236981 0.9998976 -0.007203757 0.01234108 0.9998986 -0.007124245 0.01234859 0.9998994 -0.006997287 0.01237118 0.999898 -0.007142126 0.01234948 0.999899 -0.007050395 -0.5687727 0.04560452 0.8212295 -0.5751828 0.01380956 0.8179084 -0.5746537 0.01465082 0.8182657 -0.5743664 0.01489299 0.8184629 -0.5755165 0.01342403 0.81768 -0.5735368 0.01305949 0.8190758 -0.5734862 0.01296007 0.8191128 -0.5734968 0.01292914 0.8191058 -0.5735016 0.01293987 0.8191022 -0.5734528 0.01292526 0.8191366 -0.5735047 0.01290857 0.8191006 -0.5735232 0.01294529 0.8190872 -0.5735026 0.01291203 0.8191021 -0.5734663 0.01295292 0.8191269 -0.5734711 0.01293921 0.8191237 -0.5735101 0.01293528 0.8190965 -0.5734852 0.01297867 0.8191133 -0.5734761 0.01293545 0.8191202 -0.5735093 0.01296073 0.8190966 -0.5735074 0.01291668 0.8190986 -0.5734992 0.01293116 0.8191041 -0.5735121 0.01293271 0.8190951 -0.573516 0.01293772 0.8190923 -0.5735078 0.01295179 0.8190978 -0.573489 0.01293808 0.8191111 -0.5735092 0.01293802 0.8190971 -0.5734981 0.01293826 0.8191047 -0.5734925 0.01294976 0.8191085 -0.5734699 0.01291662 0.8191248 -0.573505 0.01294142 0.8190999 -0.573504 0.01291793 0.819101 -0.5734784 0.01291823 0.8191189 -0.5734966 0.01295572 0.8191056 -0.5735332 0.01296734 0.8190798 -0.5735625 0.01285666 0.8190611 -0.5735434 0.01281404 0.8190751 -0.5733757 0.01309669 0.819188 -0.573476 0.01307862 0.819118 -0.5735195 0.01295995 0.8190894 -0.5734649 0.01297456 0.8191274 -0.5734786 0.01292949 0.8191186 -0.5733947 0.01298558 0.8191764 -0.5734726 0.01286232 0.8191238 -0.5734982 0.01296043 0.8191043 -0.5735114 0.01296573 0.8190951 -0.5734838 0.01287853 0.8191157 -0.5734595 0.01304292 0.8191301 -0.5734876 0.01290512 0.8191126 -0.573495 0.01289808 0.8191075 -0.5734863 0.01290291 0.8191136 -0.573504 0.01291322 0.8191011 -0.5735126 0.01292091 0.8190948 -0.5734958 0.01293051 0.8191065 -0.5734896 0.01290994 0.8191112 -0.5734847 0.01298767 0.8191133 -0.5734973 0.01294773 0.8191052 -0.5734751 0.01294863 0.8191208 -0.5734663 0.01302349 0.8191257 -0.5735257 0.01291745 0.8190857 -0.5735562 0.01291811 0.8190645 -0.5735085 0.0129854 0.8190968 -0.573509 0.01289063 0.8190979 -0.5734385 0.01293212 0.8191466 -0.5734621 0.012941 0.81913 -0.1689302 0.9455473 0.2782139 -0.160051 0.9529789 0.2573229 -0.3890669 0.7301877 0.5616519 -0.3000681 0.8255988 0.4778552 -0.5330293 0.3678739 0.7619374 -0.4548401 0.5662777 0.68735 -0.5368786 0.3210346 0.7801911 0.03237205 0.9994205 -0.01052546 0.02984154 0.9995416 0.00510627 0.01696819 0.9997652 0.01348066 0.0304268 0.9995189 0.006025671 -0.5734879 0.01296639 0.8191114 -0.5785734 0.01412969 0.815508 -0.5733594 0.01226407 0.8192123 -0.5734951 0.01294875 0.8191066 -0.5735216 0.01295828 0.8190879 -0.5734933 0.01291418 0.8191086 -0.5734802 0.01294499 0.8191171 -0.5734658 0.0129621 0.819127 -0.01449477 -0.9997376 -0.01774126 -0.03117173 -0.9994959 -0.006032764 -0.03496897 -0.9992364 0.01743561 -0.0324074 -0.9994429 -0.007975697 0.5735856 -0.01308369 -0.8190412 0.5735069 -0.01296478 -0.8190982 0.5734925 -0.01294797 -0.8191085 0.5734892 -0.01283055 -0.8191127 0.5734933 -0.01295089 -0.819108 0.573504 -0.01295417 -0.8191004 0.5734974 -0.01290899 -0.8191058 0.5735012 -0.01293188 -0.8191028 0.573515 -0.01293021 -0.819093 0.5734935 -0.01309502 -0.8191054 0.5734976 -0.01292121 -0.8191054 0.5734985 -0.01292502 -0.8191047 0.5736184 -0.01294857 -0.8190204 0.5725424 -0.01097315 -0.8198016 0.5735293 -0.01296317 -0.8190826 0.5734545 -0.01295602 -0.819135 0.5721837 -0.011491 -0.820045 0.5735051 -0.01293456 -0.8190999 0.573507 -0.01293438 -0.8190987 0.5735346 -0.01297932 -0.8190785 0.5734928 -0.01294124 -0.8191084 0.5734916 -0.01294285 -0.8191092 0.5734701 -0.01295119 -0.8191242 0.5734706 -0.01287508 -0.8191251 0.5734849 -0.01295274 -0.8191137 0.573493 -0.0129559 -0.8191081 0.5734509 -0.01288175 -0.8191387 0.573484 -0.01296228 -0.8191142 0.5734998 -0.01293468 -0.8191037 0.5718126 -0.01205927 -0.8202957 0.5734943 -0.01295602 -0.8191072 0.573481 -0.01294022 -0.8191168 0.5775765 0.0206052 -0.8160765 0.573516 -0.01296097 -0.8190918 0.5734876 -0.01290661 -0.8191127 0.5735064 -0.01290667 -0.8190994 0.5735568 -0.01296204 -0.8190633 0.5734548 -0.01293867 -0.819135 0.5734472 -0.01300287 -0.8191395 0.5735116 -0.0129134 -0.8190957 0.5734838 -0.01297658 -0.8191142 0.5735248 -0.01288348 -0.8190869 0.5734835 -0.01289391 -0.8191156 0.5735136 -0.01296979 -0.8190934 0.5735237 -0.01286679 -0.819088 0.5734793 -0.01289796 -0.8191186 0.573481 -0.012928 -0.8191168 0.5734754 -0.01293116 -0.8191207 0.5735006 -0.012946 -0.8191029 0.573489 -0.01300263 -0.8191102 0.5734727 -0.01293236 -0.8191226 0.5735023 -0.01291811 -0.8191021 0.5735108 -0.01293784 -0.8190959 0.5735099 -0.01291793 -0.8190968 0.5735275 -0.01293933 -0.8190841 0.5734905 -0.01292324 -0.8191103 0.5734885 -0.01293814 -0.8191115 0.5734989 -0.01294106 -0.8191041 0.5734612 -0.01278364 -0.819133 0.5734984 -0.01293402 -0.8191046 0.5735489 -0.01297539 -0.8190686 0.573498 -0.01294714 -0.8191047 0.5418412 0.3437141 -0.7669869 0.5489569 0.3246759 -0.7702156 0.4127801 0.7120535 -0.5679722 0.4357801 0.683035 -0.586139 0.217943 0.9368065 -0.2736686 0.2339573 0.9284956 -0.2883747 0.5734761 -0.01293808 -0.8191202 0.5734892 -0.01292085 -0.8191113 0.5735058 -0.01301687 -0.8190982 0.5734759 -0.01291382 -0.8191207 0.5734735 -0.01295077 -0.8191218 0.5734776 -0.01301783 -0.819118 0.574916 -0.008715331 -0.8181661 0.5715698 -0.008247733 -0.820512 -0.9878891 0.09646528 0.1215305 -0.3545091 -0.01433312 0.9349427 -0.2674167 -0.08888226 0.959473 -0.4007083 0.3413846 0.850229 -0.2171854 0.4639188 0.8588422 -0.2035759 -0.07904648 -0.975863 0.2422677 0.2948928 -0.9243077 -0.724019 0.04788839 -0.6881157 -0.9026342 0.2236973 0.3677105 -0.7844518 0.01414555 0.6200286 0.5375816 -0.1744543 -0.8249678 0.4683102 -0.01221847 -0.8834797 0.4068147 0.4767847 0.7792165 0.7965898 0.00400108 0.6045071 0.06331163 0.9976462 -0.02634 -0.2925196 0.9093031 -0.2959735 -0.2630013 0.9569969 -0.1224222 -0.7649664 -0.3343213 -0.5505049 -0.5780233 0.7316722 -0.36131 -0.7839447 -0.3635022 -0.5032861 -0.4882049 0.7710164 -0.4088886 -0.5469408 -0.7297763 -0.4102224 -0.708077 0.4091701 -0.5755056 -0.7233214 0.531926 -0.4402965 -0.557128 -0.7579588 -0.3392741 -0.8064935 0.07753568 -0.5861369 -0.8407218 0.1371777 -0.5238026 -0.2353658 -0.9545688 -0.1827607 0.01281714 -0.999611 0.02477401 -0.2322837 -0.9614028 -0.1474756 0.01683902 -0.9980196 0.06060957 0.3717203 -0.89793 0.2356812 0.3670306 -0.8771686 0.3096188 0.6744841 -0.5907551 0.4428091 0.6772617 -0.5979653 0.4286656 0.7392598 -0.307192 0.5992729 0.8593145 -0.148584 0.4893888 0.8088553 0.3271646 0.4885861 0.7812836 0.08450239 0.6184298 0.7380908 0.3998543 0.5434508 0.5833309 0.7289903 0.3581874 0.5959731 0.7222306 0.3509973 0.2865784 0.9518596 0.1087943 0.3149402 0.9059339 0.2830131 -0.03859513 0.9991819 0.01208901 0.8193661 0.04126638 0.5717834 0.8110423 0.1448736 0.5667645 0.8075796 0.1821088 0.5609381 0.780195 0.309874 0.5433912 0.7705456 0.3495494 0.5329868 0.7326089 0.4548167 0.5063854 0.7245466 0.475705 0.4987354 0.6274592 0.64847 0.4310241 0.4806558 0.8147182 0.3243522 0.618043 0.6636512 0.4214143 0.3122904 0.9275006 0.2054685 0.4692005 0.8253411 0.3141068 0.2950677 0.9363247 0.1903445 0.12049 0.9900832 0.0722332 0.0942493 0.994278 0.05028426 0.8178668 0.06264305 0.5719876 -0.2184995 0.9246454 0.3119118 -0.2589886 0.9118136 0.3186233 -0.5481867 0.1998611 0.812125 -0.5056991 0.4233154 0.7517131 -0.5770576 0.2991263 0.7599527 -0.3926665 0.7103604 0.5841243 -0.4610981 0.66118 0.5918019 -0.4861071 -0.8076944 -0.333661 -0.5477545 -0.7524013 -0.3658651 -0.3058197 -0.9299578 -0.204091 -0.3706828 -0.8974717 -0.2390373 -0.1231312 -0.9897628 -0.07217043 -0.1162443 -0.9910435 -0.0657286 -0.8182187 -0.0584045 -0.5719329 -0.8183103 -0.05718404 -0.5719251 -0.8099648 -0.1583735 -0.5646902 -0.8087663 -0.171672 -0.5625174 -0.7916743 -0.2622058 -0.5518152 -0.7754058 -0.3352192 -0.5351393 -0.7582367 -0.3852609 -0.5259764 -0.6826508 -0.5615075 -0.4676509 -0.6853485 -0.5551033 -0.4713364 -0.2437547 -0.9689823 -0.0407074 -0.0208835 -0.9969137 -0.07567691 -0.7754813 0.3456827 -0.5283299 -0.5905904 -0.7542163 -0.2869858 -0.3514725 -0.8695122 -0.3470097 -0.7374878 0.3746275 -0.5619306 -0.5823273 0.7154684 -0.3860052 -0.7869771 -0.3980516 -0.4714042 -0.633787 -0.5488864 -0.5450117 -0.3471175 0.9018545 -0.2572314 -0.5527793 0.7318441 -0.3985464 -0.8272919 -0.06546449 -0.557945 -0.7810332 -0.125177 -0.6118153 -0.3135802 0.9112516 -0.2669981 -0.04790335 0.9987195 -0.0162689 0.1976968 0.9604676 0.1960051 0.06413495 0.9969997 -0.04334062 0.482879 0.7566553 0.4407956 0.4591895 0.8670927 0.1931197 0.7286012 0.3692818 0.5768633 0.6998219 0.5863747 0.407939 0.7996678 0.2966575 0.52204 0.7952268 -0.1044513 0.5972474 0.7880056 -0.09526455 0.6082531 0.7784717 -0.410582 0.4747679 0.6203868 -0.5513782 0.5577656 0.3722109 -0.8592442 0.3509397 0.5718433 -0.7644252 0.2977405 0.1850119 -0.9785971 0.09010267 0.182497 -0.9630947 0.1978475 0.1884962 0.9054488 -0.3803048 0.1930279 0.9532501 -0.2324964 0.5694098 0.1833749 -0.8013402 0.55704 0.1986981 -0.8063657 0.5202721 0.4485033 -0.7267475 0.5020079 0.4627843 -0.7306291 0.3935695 0.6703097 -0.6291168 0.4037731 0.7605808 -0.5084134 0.01238346 0.9998986 -0.007036149 0.01236021 0.9998981 -0.007147908 0.01236766 0.9998965 -0.007358253 0.01223719 0.999899 -0.007239878 0.01227378 0.9998998 -0.007056951 0.01236337 0.9998978 -0.007188558 0.0123831 0.9998987 -0.007023036 -0.5735517 0.01327913 0.8190617 -0.573485 0.0129106 0.8191144 -0.5734748 0.01281505 0.819123 -0.5735058 0.01286315 0.8191006 -0.5736621 0.01265984 0.8189944 -0.5734756 0.0129745 0.8191199 -0.5735028 0.01289373 0.8191022 -0.5735036 0.01292288 0.8191012 -0.5734873 0.01295626 0.8191121 -0.5734912 0.01296973 0.8191091 -0.5734989 0.01291835 0.8191046 -0.5734816 0.01298415 0.8191155 -0.5736052 0.0130347 0.8190283 -0.573476 0.01296448 0.8191198 -0.002814769 0.9999297 -0.01151794 -0.02586489 0.9990758 -0.0343306 0.5734738 -0.01287734 -0.8191227 0.5736044 -0.01317924 -0.8190265 0.5734996 -0.01296979 -0.8191032 0.5734956 -0.0129311 -0.8191066 0.5736078 -0.01304882 -0.8190261 0.5734739 -0.01292502 -0.8191218 0.5734586 -0.01279896 -0.8191345 0.5734993 -0.01295119 -0.8191037 0.573499 -0.0129413 -0.819104 0.5734429 -0.01293659 -0.8191434 0.5734996 -0.01293027 -0.8191038 0.573513 -0.01298677 -0.8190937 0.5734694 -0.01294392 -0.8191249 0.5899343 0.01623421 0.8072881 0.9213887 0.3660157 0.1306732 -0.8723058 -0.1936359 0.448985 -0.9827368 0.08620828 -0.1636965 0.4274728 -0.08478206 -0.900044 0.3168359 -0.02725434 -0.9480888 0.01231086 0.9999 -0.006969928 -0.6923341 0.03379589 0.7207852 -0.3729676 -0.03510361 0.9271801 -0.4997177 0.03335893 0.8655458 -0.1330828 -0.03430426 0.9905111 -0.2780796 0.03265976 0.9600027 0.921388 -0.004097521 0.3886224 0.9199796 0 0.3919664 0.1150264 -0.03324806 0.992806 -0.04024434 0.03174257 0.9986855 0.9886999 -0.007904529 0.1497001 0.9870413 0.003918886 0.1604186 0.3560571 -0.03195995 0.9339175 0.1999275 0.03056597 0.9793338 0.9950727 -0.01147681 -0.09848266 0.9967271 0.007659375 -0.08047646 0.9401037 -0.01482546 -0.3405661 0.5494102 -0.01947671 0.8353258 0.9484745 0.01112186 -0.3166584 0.428507 0.02913981 0.9030685 0.6945565 -0.01687568 0.7192402 0.6320987 0.03377336 0.7741516 0.8272019 -0.017928 -0.5616189 0.8451105 0.01433914 -0.5343993 0.8157991 0 0.5783354 0.7991994 0.02404874 0.6005849 0.6633375 -0.02078491 -0.7480317 0.6926127 0.0173043 -0.7211022 0.4585853 -0.02339512 -0.8883424 0.4999043 0.0200439 -0.8658487 0.2256163 -0.02575767 -0.9738758 0.2781425 0.0225324 -0.9602756 -0.02123349 -0.02787631 -0.9993859 0.04025268 0.02478295 -0.9988822 -0.2667512 -0.02974689 -0.9633063 -0.199957 0.02677935 -0.9794387 -0.4285163 0.02853977 -0.9030833 -0.4958086 -0.03136968 -0.8678652 -0.6321631 0.03004157 -0.7742528 -0.6942911 -0.03278553 -0.7189472 -0.7990377 0.031304 -0.6004655 -0.8499569 -0.03395503 -0.5257571 -0.9532492 -0.0348137 -0.3001736 -0.9195075 0.03233802 -0.39174 -0.9865065 0.03315252 -0.1603302 -0.997797 -0.03546011 -0.05606919 -0.9808521 -0.0359283 0.1914111 -0.9961951 0.03363484 0.08039844 -0.903457 -0.03606158 0.4271593 -0.947986 0.03395605 0.3164959 -0.7704015 -0.03596156 0.6365441 -0.8446922 0.03400164 0.5341715 -0.5898661 -0.035672 0.8067129 0 -1 9.77957e-6 0 -1 6.8687e-6 0 -1 -6.65726e-6 0 -1 -2.11534e-6 0 -1 -1.95618e-5 0 -1 -4.89045e-6 0 -1 7.13369e-6 0 -1 -3.49186e-7 0 1 -1.33479e-6 0 1 -1.06774e-5 0 1 5.44314e-6 0 1 1.92516e-7 0 1 -1.06762e-5 0 1 -1.06765e-5 0 1 -3.10243e-7 0 1 6.78469e-7 0 1 0 0 1 -6.2052e-7 0 1 0 + + + + + + + + + + + + + + +

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

+
+
+
+ + + + -0.1455378 0.1188941 0 -0.1523663 0.1194213 0 -0.150204 0.1274146 0 -0.1428583 0.1199777 0 -0.1363286 0.06796061 0 -0.12325 0.1299999 0 -0.1234461 0.1316154 0 -0.1141188 0.1223167 0 -0.1239688 0.1123219 0 -0.1261656 0.1244449 0 -0.1249476 0.1255239 0 -0.1240231 0.1268631 0 -0.1234461 0.1283846 0 -0.1351097 0.06908619 0 -0.154 0.06789523 0 -0.1301475 0.1367922 0 -0.1347872 0.1464341 0 -0.1323935 0.1363114 0 -0.1412199 0.1412199 0 -0.1349622 0.09555643 -1.37885e-7 -0.1329466 0.1015367 0 -0.1361064 0.1126826 0 -0.1261656 0.1355551 0 -0.1276064 0.1363114 0 -0.1274146 0.150204 0 -0.1360437 0.1147232 0 -0.1539987 0.1089199 0 -0.1240231 0.1331369 0 -0.1022198 0.1326214 0 -0.138678 0.1190431 0 -0.1405641 0.1198257 0 -0.1355782 0.1261494 0 -0.1453219 0.1089569 0 -0.1472849 0.1110779 0 -0.1249476 0.1344761 0 -0.1192517 0.1524065 0 -0.1338344 0.1244449 0 -0.1007817 0.1353719 0 -0.1323935 0.1236886 0 -0.136715 0.116922 0 -0.1434358 0.1081743 0 -0.1365539 0.1283846 0 -0.1003741 0.1375592 0 -0.1479563 0.1132768 0 -0.1308135 0.1232992 0 -0.1004513 0.1404564 0 -0.1411417 0.1080223 0 -0.13675 0.1299999 0 -0.1342223 0.09921234 0 -0.1464341 0.1347872 0 -0.1013295 0.1438159 0 -0.1291864 0.1232992 0 -0.1478935 0.1153174 0 -0.1033462 0.1475937 0 -0.1365539 0.1316154 0 -0.1276064 0.1236886 0 -0.1088464 0.1539753 -1.65757e-7 -0.1077022 0.1536612 0 -0.1359768 0.1331369 0 -0.1384621 0.1091059 0 -0.1346146 0.134986 0 -0.1469379 0.1174084 0 -0.1370621 0.1105916 0 -0.1276064 0.1236886 0.02199995 -0.1291864 0.1232992 0.02199995 -0.1308135 0.1232992 0.02199995 -0.1323935 0.1236886 0.02199995 -0.13675 0.1299999 0.02199995 -0.1365539 0.1316154 0.02199995 -0.1338344 0.1244449 0.02199995 -0.1359768 0.1331369 0.02199995 -0.1350524 0.1255239 0.02199995 -0.1350524 0.1344761 0.02199995 -0.1359768 0.1268631 0.02199995 -0.1338344 0.1355551 0.02199995 -0.1365539 0.1283846 0.02199995 -0.1323935 0.1363114 0.02199995 -0.1298524 0.1367922 0.02199995 -0.1276064 0.1363114 0.02199995 -0.1253854 0.134986 0.02199995 -0.1240231 0.1331369 0.02199995 -0.1234461 0.1316154 0.02199995 -0.1232712 0.1291826 0.02199995 -0.1240231 0.1268631 0.02199995 -0.1253853 0.125014 0.02199995 -0.134903 0.09620875 0.001999735 -0.1350651 0.0692256 0.001999974 -0.1361889 0.0680055 0.001999914 -0.154 0.06789523 0.001999974 -0.154 0.1080999 0.001999974 -0.1540028 0.1083011 0.002999961 -0.1522856 0.1199969 0.003000378 -0.1516752 0.1227782 0.001999974 -0.1516752 0.1227782 0.002999961 -0.1487057 0.1308138 0.001999974 -0.1440851 0.1380276 0.001999974 -0.1380276 0.1440851 0.001999974 -0.1308138 0.1487057 0.001999974 -0.1227782 0.1516752 0.001999974 -0.1227782 0.1516752 0.002999961 -0.119906 0.1523041 0.003000378 -0.1085745 0.1539557 0.002999484 -0.1083286 0.1539288 0.001999914 -0.1074148 0.1533721 0.001999974 -0.1024503 0.146211 0.002000153 -0.1012753 0.1436727 0.001999974 -0.1003768 0.1402934 0.00199902 -0.1004066 0.1372552 0.001999974 -0.1010009 0.1347525 0.002000212 -0.102463 0.1323744 0.001999735 -0.1239688 0.1123219 0.001999974 -0.1337728 0.1003177 0.002000331 -0.1141188 0.1223167 0.001999974 -0.1472849 0.116922 0.02199995 -0.1479563 0.1147232 0.02199995 -0.1428583 0.1080223 0.02199995 -0.1399821 0.1083081 0.02199995 -0.1478935 0.1126827 0.02199995 -0.1380213 0.1095089 0.02199995 -0.1469379 0.1105916 0.02199995 -0.136715 0.111078 0.02199995 -0.1455378 0.1091059 0.02199995 -0.1359624 0.1138688 0.02199995 -0.1365931 0.1166897 0.02199995 -0.1384621 0.1188941 0.02199995 -0.1411417 0.1199777 0.02199995 -0.1434358 0.1198257 0.02199995 -0.1453219 0.1190431 0.02199995 0 0.1621472 0.02199995 0.1606672 0.04709297 0.02199995 0.1562332 0.09399992 0.02199995 -0.04709303 -0.1606672 0.02199995 -0.09399992 -0.1562332 0.02199995 -0.09292113 -0.1322134 0.02199995 0.1399964 -0.1429733 0.02199995 0.1456227 -0.1367247 0.02199995 0.1346146 -0.1349861 0.02199995 0.1359768 -0.1331369 0.02199995 0.1331939 -0.1479156 0.02199995 0.1323935 -0.1363114 0.02199995 0.1367287 -0.1308173 0.02199995 0.1301475 -0.1367922 0.02199995 0.1498269 -0.1294428 0.02199995 0.1258383 -0.1511905 0.02199995 -0.1091059 -0.1455378 0.02199995 -0.1105916 -0.1469379 0.02199995 0.1365539 -0.1283846 0.02199995 0.1453219 -0.1190431 0.02199995 0.1513736 -0.1246825 0.02199995 0.1472849 -0.116922 0.02199995 -0.1126827 -0.1478935 0.02199995 0.1276064 -0.1363114 0.02199995 -0.1080223 -0.1428583 0.02199995 0.1434358 -0.1198257 0.02199995 -0.1083081 -0.1399821 0.02199995 -0.1621472 0 0.02199995 -0.1563475 -0.09316283 0.02199995 0.1479563 -0.1147232 0.02199995 -0.1513736 -0.1246825 0.02199995 0.1411417 -0.1199777 0.02199995 0.09399992 0.1562332 0.02199995 0.1359768 -0.1268631 0.02199995 0.1105916 0.1469379 0.02199995 0.1126827 0.1478935 0.02199995 0.1091059 0.1455378 0.02199995 0.1080223 0.1428583 0.02199995 0.1172879 0.1530838 0.02199995 0.1261656 -0.1355551 0.02199995 0.1478935 -0.1126827 0.02199995 0.04709303 0.1606672 0.02199995 -0.1095089 -0.1380213 0.02199995 0.1346146 -0.125014 0.02199995 0.1513736 0.1246825 0.02199995 0.1249476 -0.1344761 0.02199995 -0.111078 -0.136715 0.02199995 0.1384621 -0.1188941 0.02199995 -0.1258383 -0.1511905 0.02199995 -0.1147232 -0.1479563 0.02199995 -0.116922 -0.1472849 0.02199995 -0.1190431 -0.1453219 0.02199995 0.1240231 -0.1331369 0.02199995 -0.1198257 -0.1434358 0.02199995 0.1323935 -0.1236886 0.02199995 0.1365931 -0.1166897 0.02199995 0.1308135 -0.1232992 0.02199995 -0.1331939 -0.1479156 0.02199995 0.1359624 -0.1138688 0.02199995 0.1291864 -0.1232992 0.02199995 -0.1138688 -0.1359624 0.02199995 0.1562332 -0.09399992 0.02199995 0.1469379 -0.1105916 0.02199995 0.1455378 -0.1091059 0.02199995 -0.1188941 -0.1384621 0.02199995 -0.1249476 -0.1344761 0.02199995 0.1428583 -0.1080223 0.02199995 -0.1261656 -0.1355551 0.02199995 -0.1199777 -0.1411417 0.02199995 0.1343938 0.1248183 0.02199995 -0.1240231 -0.1331369 0.02199995 -0.1166897 -0.1365931 0.02199995 0.1359768 0.1268631 0.02199995 0.1498269 0.1294428 0.02199995 -0.1276064 -0.1363114 0.02199995 0.1323935 0.1236886 0.02199995 -0.1234461 -0.1316154 0.02199995 0.1365539 0.1283846 0.02199995 -0.1301475 -0.1367922 0.02199995 0.1240231 -0.1268631 0.02199995 0.1249476 -0.1255239 0.02199995 0.1261656 -0.1244449 0.02199995 0.1308135 0.1232992 0.02199995 0.1276064 -0.1236886 0.02199995 -0.12325 -0.1299999 0.02199995 0.1234461 -0.1283846 0.02199995 0.13675 0.1299999 0.02199995 0.12325 -0.1299999 0.02199995 0.1456227 0.1367247 0.02199995 0.136715 -0.111078 0.02199995 0.1291864 0.1232992 0.02199995 -0.1606672 0.04709321 0.02199995 -0.1234461 -0.1283846 0.02199995 0.1365539 0.1316154 0.02199995 -0.1323935 -0.1363114 0.02199995 0.1234461 -0.1316154 0.02199995 0.1020571 0.1248427 0.02199995 0.1276064 0.1236886 0.02199995 0.1385772 -0.1090416 0.02199995 -0.1399964 -0.1429733 0.02199995 0.09399992 -0.1562332 0.02199995 -0.1240231 -0.1268631 0.02199995 0.1405641 -0.1081743 0.02199995 0.1359768 0.1331369 0.02199995 -0.1346146 -0.1349861 0.02199995 0.1253853 0.125014 0.02199995 0.1346146 0.1349861 0.02199995 -0.1253853 -0.125014 0.02199995 0.1606672 -0.04709303 0.02199995 0.04709297 -0.1606672 0.02199995 0.1240231 0.1268631 0.02199995 0.1399964 0.1429733 0.02199995 -0.04709297 0.1606672 0.02199995 -0.09399992 0.1562332 0.02199995 -0.1562332 0.09399992 0.02199995 0.1323935 0.1363114 0.02199995 0.1234461 0.1283846 0.02199995 -0.1276064 -0.1236886 0.02199995 -0.1365539 -0.1316154 0.02199995 -0.13675 -0.1299999 0.02199995 -0.1456227 -0.1367247 0.02199995 -0.1359768 -0.1331369 0.02199995 -0.1291864 -0.1232992 0.02199995 -0.1308135 -0.1232992 0.02199995 0.1301475 0.1367922 0.02199995 0.1331939 0.1479156 0.02199995 0.1240231 0.1331369 0.02199995 0.1249476 0.1344761 0.02199995 0.1188941 0.1384621 0.02199995 0.1234461 0.1316154 0.02199995 0.1166897 0.1365931 0.02199995 0.1621472 0 0.02199995 0.1261656 0.1355551 0.02199995 0.12325 0.1299999 0.02199995 -0.1498269 -0.1294428 0.02199995 -0.1365539 -0.1283846 0.02199995 -0.1359768 -0.1268631 0.02199995 0.1276064 0.1363114 0.02199995 0.1199777 0.1411417 0.02199995 0.1138688 0.1359624 0.02199995 0 -0.1621472 0.02199995 -0.1323935 -0.1236886 0.02199995 0.1198257 0.1434358 0.02199995 0.111078 0.136715 0.02199995 0.1190431 0.1453219 0.02199995 0.1255125 0.1513355 0.02199995 -0.1343938 -0.1248183 0.02199995 0.1095089 0.1380213 0.02199995 0.116922 0.1472849 0.02199995 0.1083081 0.1399821 0.02199995 -0.1513763 0.1246654 0.02199995 -0.1258921 0.1511819 0.02199995 0.1147232 0.1479563 0.02199995 -0.1498862 0.1293089 0.02199995 -0.1333207 0.1478421 0.02199995 -0.1457086 0.136606 0.02199995 -0.1401051 0.142875 0.02199995 0.107681 0.1536418 0.001999974 0.09399992 0.1562332 0.001999974 0.1562332 0.09399992 0.001999974 0.1539288 0.1083286 0.001999914 0.1087849 0.153976 0.001999974 -0.108497 -0.1539371 0.001999974 -0.1076062 -0.1535859 0.001999914 -0.09399992 -0.1562332 0.001999974 -0.1033462 -0.1475937 0.001999974 -0.1013157 -0.1438006 0.001999974 -0.1004482 -0.1404433 0.001999974 0.11925 0.1524115 0.001999974 0.1172879 0.1530838 0.001999974 -0.1003797 -0.1375034 0.001999974 0.1255125 0.1513355 0.001999974 0.1283183 0.1498423 0.001999974 0.1498269 0.1294428 0.001999974 0.1513736 0.1246825 0.001999974 0.1483949 0.1314251 0.001999974 0.1331939 0.1479156 0.001999974 0.1363922 0.1453326 0.001999974 -0.1329466 -0.1015367 0.001999974 -0.134221 -0.09921574 0.001999914 0.1432072 0.1390811 0.001999974 0.1456227 0.1367247 0.001999974 -0.1349425 -0.09571015 0.002000153 0.1399964 0.1429733 0.001999974 -0.1562332 -0.09399992 0.001999974 -0.154 -0.07736492 0.001999974 -0.154 -0.1080999 0.001999974 -0.1562332 0.09399992 0.001999974 0.1516752 0.1227782 0.001999974 -0.1239688 -0.1123219 0.001999974 -0.1606672 -0.04709285 0.001999974 -0.1008953 -0.1351287 0.001999974 -0.04709285 -0.1606672 0.001999974 -0.1021878 -0.1326556 0.002000093 -0.1374963 -0.06790906 0.001999974 -0.1350185 -0.06957072 0.001999974 -0.1141188 -0.1223167 0.001999974 -0.1362079 -0.06802511 0.001999974 0 -0.1621472 0.001999974 -0.1353388 -0.06875896 0.001999974 -0.1621472 0 0.001999974 -0.1606672 0.04709285 0.001999974 0.09399992 -0.1562332 0.001999974 0.1076056 -0.1535848 0.001999914 0.1084982 -0.1539369 0.001999974 0.1035274 -0.1478524 0.001999974 0.1014693 -0.1439822 0.001999974 0.1005779 -0.1405434 0.001999974 0.04709285 -0.1606672 0.001999974 0.1004984 -0.1375787 0.001999974 0.1009153 -0.1353212 0.001999914 0.1023789 -0.1325016 0.001999974 0.1136296 -0.1227713 0.001999974 0.1533945 -0.107441 0.001999974 0.1463352 -0.1025116 0.002000212 0.1562332 -0.09399992 0.001999974 0.1423975 -0.1008226 0.002001404 0.1381238 -0.1003009 0.001999855 0.1539288 -0.1083286 0.001999914 -0.09399992 0.1562332 0.001999974 0.1324332 -0.1024193 0.001999735 0.1606672 -0.04709285 0.001999974 0.1348595 -0.1009497 0.001999676 -0.04709285 0.1606672 0.001999974 0.1621472 0 0.001999974 0.1229199 -0.1134689 0.001999974 0 0.1621472 0.001999974 0.1606672 0.04709285 0.001999974 0.1323643 0.1024711 0.001999676 0.04709285 0.1606672 0.001999974 0.1023456 0.1325373 0.002000153 0.1347525 0.1010009 0.002000212 0.1010242 0.1350903 0.001999974 0.1229199 0.1134689 0.001999974 0.1136296 0.1227713 0.001999974 0.1372552 0.1004066 0.001999974 0.1005043 0.1375221 0.001999974 0.1402934 0.1003768 0.00199902 0.1436727 0.1012753 0.001999974 0.146211 0.1024503 0.002000153 0.1014558 0.1439686 0.001999974 0.1005749 0.1405309 0.001999974 0.1035274 0.1478524 0.001999974 0.1533721 0.1074148 0.001999974 -0.1513763 0.1246654 0.001999974 -0.1258921 0.1511819 0.001999974 -0.1498862 0.1293089 0.001999974 -0.1457086 0.136606 0.001999974 -0.1401051 0.142875 0.001999974 -0.1333207 0.1478421 0.001999974 -0.1566113 -0.08999997 0.01699995 -0.1606672 -0.04709285 0.01699995 -0.1516752 -0.1227782 0.001999974 -0.1513736 -0.1246825 0.001999974 -0.1518945 -0.1218606 0.002998769 -0.154003 -0.1085832 0.002999961 -0.1498269 -0.1294428 0.001999974 -0.1456227 -0.1367247 0.001999974 -0.1399964 -0.1429733 0.001999974 -0.1331939 -0.1479156 0.001999974 -0.1258383 -0.1511905 0.001999974 -0.1086385 -0.1539618 0.002999484 -0.1227782 -0.1516752 0.001999974 -0.1227782 -0.1516752 0.002999961 0.1227782 -0.1516752 0.001999974 0.1258383 -0.1511905 0.001999974 0.1227782 -0.1516752 0.002999961 0.1085934 -0.153959 0.002999365 0.1331939 -0.1479156 0.001999974 0.1399964 -0.1429733 0.001999974 0.1456227 -0.1367247 0.001999974 0.1498269 -0.1294428 0.001999974 0.1513736 -0.1246825 0.001999974 0.1539595 -0.1086221 0.002999722 0.1516752 -0.1227782 0.001999974 0.1516752 -0.1227782 0.002999961 0.1516752 0.1227782 0.002999961 0.1539557 0.1085745 0.002999663 -0.1253854 -0.134986 0 -0.1276064 -0.1363114 0 -0.1298524 -0.1367922 0 -0.13675 -0.1299999 0 -0.1365539 -0.1283846 0 -0.1359768 -0.1268631 0 -0.1323935 -0.1363114 0 -0.1346146 -0.125014 0 -0.1343937 -0.1351817 0 -0.1323935 -0.1236886 0 -0.1359768 -0.1331369 0 -0.1365539 -0.1316154 0 -0.1308135 -0.1232992 0 -0.1291864 -0.1232992 0 -0.1276064 -0.1236886 0 -0.1261656 -0.1244449 0 -0.1249476 -0.1255239 0 -0.1240231 -0.1268631 0 -0.1234461 -0.1283846 0 -0.12325 -0.1299999 0 -0.1234461 -0.1316154 0 -0.1240231 -0.1331369 0 -0.1174084 -0.1469379 0 -0.1188941 -0.1455378 0 -0.1153174 -0.1478935 0 -0.1080223 -0.1411417 0 -0.1132768 -0.1479563 0 -0.1091059 -0.1384621 0 -0.1110779 -0.1472849 0 -0.1105916 -0.1370621 0 -0.1089569 -0.1453219 0 -0.1126826 -0.1361064 0 -0.1081743 -0.1434358 0 -0.1147232 -0.1360437 0 -0.116922 -0.136715 0 -0.1190431 -0.138678 0 -0.1198257 -0.1405641 0 -0.1199777 -0.1428583 0 0.1174084 0.1469379 0 0.1153174 0.1478935 0 0.1080223 0.1411417 0 0.1132768 0.1479563 0 0.1091059 0.1384621 0 0.1110779 0.1472849 0 0.1105916 0.1370621 0 0.1089569 0.1453219 0 0.1126826 0.1361064 0 0.1081743 0.1434358 0 0.1147232 0.1360437 0 0.116922 0.136715 0 0.1190431 0.138678 0 0.1198257 0.1405641 0 0.1199777 0.1428583 0 0.1188941 0.1455378 0 0.1343937 -0.1351817 0 0.1323935 -0.1363114 0 0.1298524 -0.1367922 0 0.1232712 -0.1291826 0 0.1276064 -0.1363114 0 0.1240231 -0.1268631 0 0.1253854 -0.134986 0 0.1253854 -0.125014 0 0.1240231 -0.1331369 0 0.1234461 -0.1316154 0 0.1276064 -0.1236886 0 0.1291864 -0.1232992 0 0.1308135 -0.1232992 0 0.1323935 -0.1236886 0 0.1338344 -0.1244449 0 0.1350524 -0.1255239 0 0.1359768 -0.1268631 0 0.1365539 -0.1283846 0 0.13675 -0.1299999 0 0.1365539 -0.1316154 0 0.1359768 -0.1331369 0 0.1469379 -0.1174084 0 0.1478935 -0.1153174 0 0.1412733 -0.1080189 0 0.1392117 -0.1086873 0 0.1479563 -0.1132768 0 0.1472849 -0.1110779 0 0.1373939 -0.1100945 0 0.1453219 -0.1089569 0 0.1361064 -0.1126826 0 0.1434358 -0.1081743 0 0.1360437 -0.1147232 0 0.136715 -0.116922 0 0.138678 -0.1190431 0 0.1405641 -0.1198257 0 0.1428583 -0.1199777 0 0.1455378 -0.1188941 0 0.1346146 0.125014 0 0.1323935 0.1236886 0 0.1308135 0.1232992 0 0.12325 0.1299999 0 0.1234461 0.1316154 0 0.1291864 0.1232992 0 0.1240231 0.1331369 0 0.1276064 0.1236886 0 0.1253854 0.134986 0 0.1261656 0.1244449 0 0.1249476 0.1255239 0 0.1276064 0.1363114 0 0.1240231 0.1268631 0 0.1234461 0.1283846 0 0.1298524 0.1367922 0 0.1323935 0.1363114 0 0.1343937 0.1351817 0 0.1359768 0.1331369 0 0.1365539 0.1316154 0 0.13675 0.1299999 0 0.1365539 0.1283846 0 0.1359768 0.1268631 0 -0.1378366 -0.06804579 0 -0.154 -0.07736492 0 -0.154 -0.1088125 0 -0.1621472 0 0.01699995 0.1274146 0.150204 0 0.1192688 0.1524043 0 0.1347872 0.1464341 0 0.1412199 0.1412199 0 0.1464341 0.1347872 0 0.1523041 0.119906 0.003000438 0.150204 0.1274146 0 0.1524065 0.1192517 0 0.1084833 0.1539845 0 0.1074188 0.1533764 0 0.1026431 0.1322309 2.2896e-7 0.1011538 0.1346543 1.47554e-7 0.1004167 0.1379857 1.3726e-7 0.1007772 0.1416864 0 0.102148 0.1456657 -9.95172e-7 0.1136296 0.1227713 0 0.1229199 0.1134689 0 0.1326158 0.1022238 0 0.1475937 0.1033462 0 0.1438159 0.1013295 0 0.1404564 0.1004513 0 0.1375592 0.1003741 0 0.1353719 0.1007817 0 0.1536612 0.1077022 0 0.1539753 0.1088464 -1.65757e-7 0.1539855 -0.1089549 0 0.1536445 -0.1076681 0 0.1475937 -0.1033462 0 0.1438006 -0.1013157 0 0.1404433 -0.1004482 0 0.1375034 -0.1003797 0 0.1351287 -0.1008953 0 0.1325885 -0.1022328 -1.62145e-7 0.1229199 -0.1134689 0 0.1136296 -0.1227713 0 0.10264 -0.132234 1.36781e-7 0.1011553 -0.1346439 -2.03307e-7 0.1004248 -0.1380239 0 0.1009128 -0.1423408 -1.59607e-6 0.1026482 -0.1465198 -2.66885e-7 0.1075842 -0.1535468 0 0.1086838 -0.1539845 0 -0.1074387 -0.1533922 0 -0.1084156 -0.1539661 0 -0.1025116 -0.1463352 -1.47731e-7 -0.1024669 -0.1323705 2.36004e-7 -0.1009497 -0.1348595 2.13074e-7 -0.1003009 -0.1381238 1.27482e-7 -0.1008226 -0.1423975 -9.64861e-7 -0.1141188 -0.1223167 0 -0.1239688 -0.1123219 0 -0.1349325 -0.09604042 2.58345e-7 -0.1337715 -0.1003198 -2.68251e-7 -0.1369022 -0.06787544 0 -0.1358638 -0.06823366 0 -0.1350832 -0.06919074 0 -0.1200188 -0.1522812 0.003000378 -0.1191951 -0.1524196 0 -0.1274146 -0.150204 0 -0.1308138 -0.1487057 0.001999974 -0.1347872 -0.1464341 0 -0.1380276 -0.1440851 0.001999974 -0.1412199 -0.1412199 0 -0.1440851 -0.1380276 0.001999974 -0.1464341 -0.1347872 0 -0.1487057 -0.1308138 0.001999974 -0.150204 -0.1274146 0 -0.1524093 -0.1192396 0 0.119906 -0.1523041 0.003000438 0.1522812 -0.1200188 0.003000378 0.1523663 -0.1194213 0 0.150204 -0.1274146 0 0.1487057 -0.1308138 0.001999974 0.1464341 -0.1347872 0 0.1440851 -0.1380276 0.001999974 0.1412199 -0.1412199 0 0.1380276 -0.1440851 0.001999974 0.1347872 -0.1464341 0 0.1308138 -0.1487057 0.001999974 0.1274146 -0.150204 0 0.1192512 -0.1524066 0 -0.1952189 -0.04811578 0.1635 -0.2 -0.0445789 0.1635 -0.1578007 -0.03666484 0.1635 -0.2 0.0445789 0.1635 -0.1578007 0.03666484 0.1635 -0.1952189 0.04811578 0.1635 -0.1578007 -0.03666484 0.197 -0.16096 -0.03764128 0.197 -0.160955 -0.03766226 0.202 -0.1952189 -0.04811578 0.202 -0.2 -0.0445789 0.202 -0.2 0.0445789 0.202 -0.1952189 0.04811578 0.202 -0.1609548 0.03765916 0.197 -0.1578007 0.03666484 0.197 -0.1578007 0.03666484 0.202 -0.1578007 -0.03666484 0.202 -0.1609522 0.03767293 0.202 + + + + + + + + + + 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 -1.27951e-6 5.70935e-5 -1 0 0 -1 0 0 -1 2.75382e-6 -6.8801e-6 -1 0 0 -1 0 0 -1 0 0 -1 -7.24301e-6 0 -1 0 0 -1 0 0 -1 1.16937e-6 4.4354e-7 -1 1.13634e-6 1.13984e-6 -1 0 0 -1 0 0 -1 -2.16983e-6 -2.44932e-6 -1 0 1.02559e-5 -1 -6.73912e-6 -5.74602e-7 -1 0 0 -1 -3.11391e-6 -2.14943e-6 -1 6.28572e-6 1.51491e-5 -1 0 0 -1 2.04953e-4 -8.17251e-5 -1 0 0 -1 0 0 -1 -1.27789e-5 -3.40481e-7 -1 7.57558e-7 1.14365e-5 -1 0 0 -1 5.33077e-5 3.74865e-5 -1 0 0 -1 1.10343e-6 -2.34484e-6 -1 -6.62028e-6 -1.73058e-6 -1 0 0 -1 0 0 -1 2.46946e-6 -3.53196e-6 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 4.67768e-5 -3.80056e-4 -1 -9.16189e-6 -1.15767e-5 -1 0 0 -1 4.9747e-6 4.7474e-6 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 -0.464777 0.8854278 0 -0.2392996 0.9709458 0 0 1 0 -0.2392966 0.9709465 0 0.2392996 0.9709458 0 0.9927117 -0.1205132 0 0.9927133 -0.1205003 0 0.4647717 0.8854307 0 0.2392966 0.9709465 0 0.9350054 -0.3546335 0 0.9350011 -0.3546448 0 0.6631081 0.7485237 0 0.464777 0.8854278 0 0.8229739 -0.5680702 0.003208696 0.8051269 -0.5931027 0 0.8229759 0.5680654 -0.003517627 0.6989982 0.7151143 0.003627061 0.6630945 -0.7485241 -0.004154264 0.9350011 0.3546448 0 0.9164869 0.4000484 0.003626167 0.4647681 -0.8854325 0 0.9927117 0.1205143 0 0.5124314 -0.8587188 0.004037618 0.9927132 0.1205015 0 0.1859121 -0.9825632 -0.002494096 0.2093306 -0.977845 0 -0.2093306 -0.977845 0 -0.1859121 -0.9825632 0.002494096 -0.5124205 -0.8587252 -0.004038035 -0.4647734 -0.8854297 0 -0.6631075 -0.7485128 0.004153549 -0.8229678 -0.5680791 -0.003208696 -0.8051313 -0.5930968 0 -0.9350011 -0.3546448 0 -0.9927117 -0.1205132 0 -0.9974209 -0.07168221 -0.003626883 -0.9927055 0.1205135 0.003517687 -0.951259 0.3083719 -0.003625988 -0.9350011 0.3546448 0 -0.8051311 0.593097 0 -0.8229768 0.568066 -0.003209531 -0.6630958 0.748523 0.004154324 -0.5124276 0.858721 -0.004038751 0.9996006 -0.006004929 -0.02761662 0.9997441 -0.005574166 -0.02192801 0.7351746 -0.6771783 0.03079009 0.6781066 -0.7343147 -0.03087699 0.006190717 -0.9997388 0.02200174 0.003700494 -0.9999932 0 -0.9999998 2.97957e-5 -5.98735e-4 -1 0 0 -0.9999915 -0.00357145 -0.002090454 -0.9889884 0.1451994 0.02862101 -0.9881279 0.1536059 -0.002915203 -0.9767485 0.2143883 0 -0.9776926 0.2095791 -0.01393193 -0.9320125 0.3444179 0.1128233 -0.9600523 0.2597075 -0.1041709 -0.836543 0.5358335 0.1143603 -0.885316 0.4527009 -0.106196 -0.702425 0.7024245 0.1148872 -0.7723692 0.6260631 -0.1071965 -0.5358331 0.8365433 0.1143602 -0.6260648 0.7723662 -0.107207 -0.2138926 0.9768572 0 -0.3444169 0.9320109 0.1128401 -0.4526966 0.8853192 -0.1061871 -0.2590501 0.9600635 -0.1056934 -0.209765 0.9776737 -0.01236015 -0.1442026 0.9893559 0.01951026 -0.1490782 0.9888247 0.001257717 0.09892594 0.9950917 -0.002496242 0.2644062 0.9633111 -0.04605537 0.519617 0.853015 0.04861682 0.8215558 0.5695466 0.02574324 0.8119059 0.5828873 -0.0324257 0.907471 0.4200789 0.005504071 0.8800393 0.4698028 -0.06940031 0.9663943 0.2569467 -0.007775187 0.9673749 0.2528801 -0.0154109 0.9998432 -0.009789943 0.0147584 0.9990313 0.02661782 -0.03504163 0.9723421 -0.2309139 0.0350663 0.983007 -0.1831832 -0.01187992 0.851236 -0.5233405 0.03888642 0.8852369 -0.4628301 -0.046305 0.7728509 -0.6312079 -0.06540703 0.712247 -0.701929 0 0.7685679 -0.6397683 0 0.6532967 -0.757102 0 0.7122474 -0.7019285 0 0.6545875 -0.755861 -0.0137639 0.8745613 -0.4800195 0.06873255 0.9618369 -0.2645287 -0.06996119 0.9795084 -0.1982196 0.03567039 0.9095085 -0.4156534 0.005157887 0.9564006 -0.2920125 -0.005157649 -0.09888315 0.9950692 -0.007716417 0.9995203 0.03075122 0.003681778 0.9995203 -0.03075098 -0.003681778 -0.3748846 0.9270395 0.007714331 0.9564012 0.2920107 0.005157589 0.9095062 0.4156586 -0.005157828 -0.5222265 0.8527913 -0.005156278 -0.7277587 0.6858235 -0.003682613 0.7277691 0.6858124 0.003681361 0.7339282 0.6792222 0.002600908 -0.7685424 0.6397885 0.003681004 -0.9095056 0.4156598 0.005157589 0.3832412 0.923641 -0.003681004 0.3748919 0.9270649 -0.00260061 -0.9654795 0.2603647 -0.00771737 0.06609475 0.9978001 0.005157172 -0.9995152 0.03075098 0.004886209 -0.9564107 -0.2920165 0.002217054 -0.9758929 -0.2181958 -0.004868507 -0.7339354 -0.6792144 0.002600908 -0.7627295 -0.6467124 -0.002601265 -0.3748964 -0.9270631 -0.002599716 -0.3832412 -0.923641 -0.003682315 -0.06609803 -0.9977999 0.005157768 0.06609803 -0.9977999 -0.00515747 0.3832412 -0.923641 0.003681659 0.3748964 -0.9270631 0.002599716 0.7339305 -0.6792197 -0.002600431 0.7277622 -0.6858198 -0.003681361 0 0 1 3.51102e-7 0 1 -7.31321e-7 0 1 -1.10041e-6 0 1 0 0 1 1.9644e-7 0 1 1.21742e-6 0 1 0 0 1 -7.5281e-7 0 1 1.65719e-7 0 1 -3.21251e-7 0 1 -6.26202e-7 0 1 -2.04953e-6 0 1 0 0 1 0 0 1 -1.59735e-7 0 1 0 0 1 7.3682e-7 0 1 1.50043e-6 0 1 -4.72754e-7 0 1 -5.3064e-7 0 1 0 0 1 1.12865e-6 0 1 -7.65459e-7 0 1 7.78515e-7 0 1 -1.89649e-7 0 1 5.54816e-7 0 1 1.64929e-6 0 1 -6.42918e-7 0 1 -1.34591e-7 0 1 0 0 1 1.429e-6 0 1 2.5289e-7 0 1 1.85762e-7 0 1 -2.15499e-7 0 1 4.85568e-7 0 1 1.71329e-7 0 1 -3.13342e-7 0 1 0 0 1 9.29741e-7 0 1 1.10041e-6 0 1 1.29865e-6 0 1 1.60466e-7 0 1 -7.62994e-7 0 1 -3.51102e-7 0 1 1.58292e-6 0 1 -9.75214e-7 0 1 7.31321e-7 0 1 0 0 1 3.20181e-7 0 1 0 0 1 -2.65152e-7 0 1 0 0 1 6.17907e-7 0 1 -1.17012e-6 0 1 0 0 1 2.03399e-6 0 1 2.24e-7 0 1 -8.81115e-7 0 1 0 0 1 -1.85948e-6 0 1 4.1924e-7 0 1 1.43301e-7 0 1 1.96437e-7 0 1 -9.49237e-7 0 1 -1.03081e-6 0 1 1.23803e-6 0 1 1.56671e-7 0 1 -3.71524e-7 0 1 -1.71329e-7 0 1 -1.1432e-6 0 1 -1.48487e-7 0 1 1.60007e-7 0 1 2.73906e-7 0 1 0 0 1 -1.82249e-7 0 1 0 0 1 0 0 1 1.91395e-6 0 1 -2.20106e-7 0 1 -4.78122e-7 0 1 1.21884e-6 0 1 -4.57989e-6 0 1 -1.52332e-7 0 1 1.70077e-6 0 1 2.23938e-6 0 1 -1.41253e-6 0 1 -1.70354e-7 0 1 -3.01077e-7 0 1 -1.87646e-7 0 1 1.28004e-6 0 1 1.55355e-7 0 1 -9.78382e-7 0 1 3.13049e-7 0 1 -4.48035e-7 0 1 -9.22931e-7 0 1 1.75676e-7 0 1 3.69626e-7 0 1 -6.24197e-6 -3.17e-5 -1 -1.03232e-5 -6.47993e-5 -1 3.01826e-6 3.21223e-6 -1 0 0 -1 0 0 -1 -1.72011e-6 -3.92865e-5 -1 -1.36159e-7 0 -1 -1.88509e-5 -9.03303e-5 -1 -5.3855e-6 -1.02123e-5 -1 -4.85188e-7 0 -1 1.41428e-7 0 -1 1.45086e-7 0 -1 2.69917e-4 1.21454e-4 -1 1.40959e-7 0 -1 -9.90931e-7 0 -1 1.07581e-5 7.94934e-5 -1 5.89139e-5 4.90274e-5 -1 3.18533e-5 6.71115e-5 -1 -2.58596e-5 -6.90683e-6 -1 1.57059e-5 6.00932e-6 -1 -3.27895e-7 -3.32205e-7 -1 -1.41719e-5 -1.54266e-5 -1 -4.57733e-6 -4.5188e-6 -1 0 0 -1 1.45599e-5 2.08801e-5 -1 -6.62115e-7 0 -1 3.04888e-5 1.19475e-5 -1 -2.80069e-6 9.02574e-7 -1 -2.09497e-6 0 -1 2.5832e-7 0 -1 9.64452e-5 -3.75833e-5 -1 1.03784e-5 -6.46523e-5 -1 -3.03182e-6 3.42255e-6 -1 0 0 -1 1.60028e-5 -3.70997e-5 -1 -1.75137e-5 3.43173e-5 -1 0 -2.29059e-7 -1 -3.24471e-4 2.33045e-4 -1 3.13007e-5 -8.35086e-6 -1 -3.51366e-7 1.03807e-6 -1 4.06034e-7 -3.94915e-7 -1 -3.01809e-5 1.16975e-5 -1 -2.89026e-5 7.61447e-6 -1 2.74532e-4 -7.6893e-4 -0.9999998 -2.15088e-4 2.24136e-4 -1 -8.70019e-5 1.97834e-5 -1 9.82818e-4 -3.31793e-4 -0.9999995 -3.42699e-4 1.98528e-4 -1 -6.04385e-5 3.49221e-5 -1 6.47465e-6 -2.13476e-5 -1 1.81329e-5 -7.57724e-5 -1 -2.51041e-5 1.68805e-5 -1 4.5926e-5 -1.70486e-5 -1 7.29795e-6 -6.88655e-7 -1 8.47682e-6 -8.2991e-6 -1 -1.37037e-4 2.76405e-4 -1 4.34697e-5 -9.90892e-5 -1 0 0 -1 -4.05006e-5 1.40105e-5 -1 8.70035e-6 -2.73685e-7 -1 0 0 -1 0 0 -1 0 0 -1 0 -1.41783e-7 -1 1.07955e-5 3.38554e-7 -1 -2.10737e-7 -6.69554e-6 -1 3.06024e-4 1.51165e-4 -1 -4.34238e-5 -9.17421e-5 -1 -5.07763e-5 -1.75323e-5 -1 1.04373e-5 3.01783e-5 -1 -9.91032e-5 -4.35131e-5 -1 0 0 -1 0 0 -1 -3.3174e-4 -9.82834e-4 -0.9999995 1.98531e-4 3.42749e-4 -1 3.49273e-5 6.02911e-5 -1 0 0 -1 -2.93157e-7 -3.20527e-7 -1 -2.13953e-5 -6.44473e-6 -1 -7.56854e-5 -1.80513e-5 -1 -0.9871098 0.1563413 -0.03422993 -0.9880561 0.1540953 0 -0.9876901 0.1564238 0 -0.9873206 0.1587393 -2.34627e-4 -0.9876869 0.1564338 0.001802146 -0.9876887 0.1564327 0 0.002605378 -4.18844e-4 0.9999966 -0.1564414 0.9876873 0 -0.1585283 0.9873544 -3.52661e-4 -0.1564406 0.9876875 0 -0.1584423 0.9851911 -0.06553256 -0.1543896 0.9880101 0 -0.1564338 0.9876872 0.001607537 5.34368e-4 -0.003116786 0.9999951 -5.68068e-7 0 -1 2.80795e-7 0 -1 0 0 -1 0 0 -1 -1.29104e-7 0 -1 -8.62402e-7 0 -1 4.64753e-7 0 -1 0 0 1 0 0 1 0 0 1 -0.9962598 -0.08638292 -0.002079069 -0.9955621 -0.09410709 9.05966e-7 -0.995562 -0.09410816 0 -0.9850555 -0.1560096 -0.07298535 -0.9876171 -0.1568383 0.003785192 -0.9833829 -0.1815435 0 -0.9846491 -0.1559536 -0.07838833 -0.9877662 -0.1558735 0.004623413 -0.9885149 -0.1511223 6.75117e-4 -0.9510577 -0.3090134 0 -0.9510564 -0.3090176 0 -0.8660269 -0.4999973 0 -0.8660247 -0.5000015 0 -0.7431429 -0.6691328 0 -0.5877849 -0.8090173 0 -0.5877849 -0.8090173 0 -0.4067351 -0.9135462 0 -0.406734 -0.9135467 0 -0.1562649 -0.9866193 -0.04651474 -0.1533303 -0.988175 0 -0.1564462 -0.9876866 0 -0.1596409 -0.987175 -5.28727e-4 -0.1564339 -0.9876855 0.002449572 -0.156445 -0.9876867 0 -0.09410768 -0.9955621 0 -0.09410798 -0.995562 0 -0.0314117 -0.9995065 -9.88327e-7 -0.03141146 -0.9995065 0 0.0314117 -0.9995065 0 0.0314117 -0.9995066 0 0.09410762 -0.9955621 0 0.09410792 -0.9955621 -9.88329e-7 0.1564462 -0.9876866 0 0.1589585 -0.9872853 -4.16224e-4 0.156445 -0.9876867 0 0.1563295 -0.9870206 -0.03676444 0.1564342 -0.9876865 0.001934111 0.1539756 -0.9880747 0 0.406734 -0.9135466 0 0.4067351 -0.9135462 0 0.5877849 -0.8090173 0 0.5877849 -0.8090173 0 0.7431429 -0.6691328 0 0.8660247 -0.5000015 0 0.8660269 -0.4999973 0 0.9510564 -0.3090176 0 0.9510577 -0.3090134 0 0.9844039 -0.1583181 -0.07671123 0.9881253 -0.1536504 0 0.9876878 -0.1564378 0 0.98723 -0.1593015 -2.94835e-4 0.9876859 -0.1564342 0.002194166 0.9876893 -0.1564289 0 0.9955621 -0.09410744 0 0.995562 -0.09410828 -8.03018e-7 0.9995065 -0.03141194 -2.3936e-7 0.9995065 -0.03141129 1.8531e-7 0.9995066 0.03141146 -1.85311e-7 0.9995066 0.03141194 -1.7759e-7 0.9955621 0.09410792 -5.55934e-7 0.9955621 0.09410768 0 0.9876878 0.1564378 0 0.9873547 0.1585264 -2.14822e-4 0.9876893 0.1564289 0 0.9851927 0.1584417 -0.0655111 0.9876872 0.1564338 0.001606643 0.9880102 0.1543889 0 0.9510577 0.3090134 0 0.9510564 0.3090176 0 0.8660269 0.4999973 0 0.8660247 0.5000015 0 0.7431429 0.6691328 0 0.5877849 0.8090173 0 0.5877849 0.8090173 0 0.4067388 0.9135445 0 0.4067378 0.913545 0 0.2079129 0.9781473 0 0.2079129 0.9781473 0 0.1340173 0.9909791 0 0.1340175 0.990979 0 0.09410768 0.9955621 0 0.09410798 0.995562 0 0.0314117 0.9995065 -9.88327e-7 0.03141146 0.9995065 0 -0.0314117 0.9995065 0 -0.0314117 0.9995066 0 -0.09410762 0.9955621 0 -0.09410792 0.9955621 0 -0.4100605 0.9120584 0 -0.4100626 0.9120574 0 -0.5907355 0.8068653 0 -0.5907342 0.8068662 0 -0.7455736 0.6664233 0 -0.7455708 0.6664264 0 -0.8678413 0.4968416 0 -0.8678424 0.4968395 0 -0.952174 0.3055566 0 -0.9521768 0.305548 0 -0.9955621 0.09410792 -1.72957e-6 -0.9955621 0.09410816 0 -0.5124206 0.8587252 0.004037559 -0.4647734 0.8854297 0 -0.1859121 0.9825632 -0.002494096 -0.2093306 0.977845 0 0.9927117 -0.1205143 0 0.9927132 -0.1205015 0 0.2093306 0.977845 0 0.1859121 0.9825632 0.002494096 0.7907305 -0.6121594 -0.002492845 0.5124261 0.8587278 -0.002493977 0.8051223 -0.593109 0 0.4917682 0.8707262 0 0.491784 -0.8707174 0 0.8051292 0.5930996 0 0.5124338 -0.8587232 0.002493917 0.7907263 0.612165 0.002494275 0.9350054 0.3546335 0 0.2392996 -0.9709458 0 0.9927117 0.1205132 0 0.2392966 -0.9709465 0 0.9927133 0.1205003 0 0 -1 0 -0.2392996 -0.9709458 0 -0.2392966 -0.9709465 0 -0.5124276 -0.858721 -0.004038512 -0.464777 -0.8854278 0 -0.6630958 -0.748523 0.004154324 -0.8229768 -0.568066 -0.003209531 -0.8051311 -0.593097 0 -0.9927117 -0.1205143 0 -0.9927132 -0.1205015 0 -0.9927133 0.1205003 0 -0.9927117 0.1205132 0 -0.8051269 0.5931027 0 -0.8229739 0.5680702 0.003208696 -0.6631075 0.7485128 -0.004153549 0.6858196 0.7277622 -0.003683328 0.4156559 0.9095074 0.005157589 0.2920066 0.9564025 -0.005157947 -0.9950688 -0.09888726 -0.00771594 -0.03074347 0.9995206 0.003680586 0.03074312 0.9995205 -0.003680527 -0.9270371 -0.3748903 0.007715046 -0.2920099 0.9564015 0.005157887 -0.8527954 -0.5222198 -0.005156278 -0.4156523 0.909509 -0.005156695 -0.6858184 -0.7277635 -0.003681957 -0.6792204 0.7339298 0.002601802 -0.6397977 -0.7685346 0.003682315 -0.6858196 0.7277623 0.003681361 -0.4156578 -0.9095065 0.00515753 -0.923643 0.3832364 -0.003681063 -0.9270623 0.3748984 -0.00260061 -0.9977999 0.06609654 0.005157351 -0.2603687 -0.9654785 -0.007716894 -0.0307433 -0.9995154 0.004886507 0.2920156 -0.9564111 0.00221759 0.2181926 -0.9758936 -0.004869461 0.6792232 -0.7339273 0.002599954 0.6467087 -0.7627328 -0.002599954 0.9270638 -0.3748949 -0.002601087 0.9236382 -0.3832479 -0.003680408 0.9977999 -0.06609696 0.00515747 0.9977999 0.06609737 -0.00515753 0.9236393 0.3832452 0.003681063 0.9270638 0.3748949 0.002601087 0.6792232 0.7339273 -0.002599954 -0.4156559 -0.9095074 0.005157589 -0.2920066 -0.9564025 -0.005157947 0.9950688 0.09888726 -0.00771594 0.03074347 -0.9995206 0.003680586 -0.03074312 -0.9995205 -0.003680527 0.9270371 0.3748903 0.007715046 0.2920099 -0.9564015 0.005157887 0.4156523 -0.909509 -0.005156695 0.8527954 0.5222198 -0.005156278 0.6858184 0.7277635 -0.003681957 0.6858196 -0.7277623 0.003681361 0.6792204 -0.7339298 0.002601802 0.6397977 0.7685346 0.003682315 0.4156578 0.9095065 0.00515753 0.923643 -0.3832364 -0.003681063 0.9270623 -0.3748984 -0.00260061 0.2603687 0.9654785 -0.007716894 0.9977999 -0.06609654 0.005157351 0.0307433 0.9995154 0.004886507 -0.2920156 0.9564111 0.00221759 -0.2181926 0.9758936 -0.004869461 -0.6792232 0.7339273 0.002599954 -0.6467087 0.7627328 -0.002599954 -0.9270638 0.3748949 -0.002601087 -0.9236382 0.3832479 -0.003680408 -0.9977999 0.06609696 0.00515747 -0.9977999 -0.06609737 -0.00515753 -0.9236393 -0.3832452 0.003681063 -0.9270638 -0.3748949 0.002601087 -0.6792232 -0.7339273 -0.002599954 -0.6858196 -0.7277622 -0.003683328 -0.4917682 0.8707262 0 -0.1859121 0.9825632 0.002494096 0.1859121 0.9825632 -0.002493977 0.9927055 -0.1205135 -0.003517687 0.4647734 0.8854297 0 0.951259 -0.3083719 0.003625929 0.5124206 0.8587252 0.004038572 0.6631075 0.7485128 -0.004153966 0.822983 -0.5680571 0.003210365 0.8051267 -0.5931029 0 0.8229678 0.568079 0.003208279 0.6630894 -0.7485287 -0.004154503 0.8051313 0.5930968 0 0.464777 -0.8854278 0 0.997421 0.07168221 0.003626883 0.5124312 -0.8587188 0.004038512 -0.5124269 -0.8587214 -0.004039049 -0.4647717 -0.8854307 0 -0.6631088 -0.7485116 0.004155218 -0.8051246 -0.5931059 0 -0.8229768 -0.568066 -0.003208279 -0.9350054 -0.3546335 0 -0.9974204 -0.07169085 -0.003626763 -0.9927057 0.1205124 0.003518342 -0.951259 0.3083719 -0.003626286 -0.9350054 0.3546335 0 -0.8051292 0.5930996 0 -0.7907263 0.612165 0.002494275 -0.5124261 0.8587278 -0.002493679 -0.9095085 0.4156534 0.005157887 -0.9564006 0.2920125 -0.005157649 0.06609362 -0.9978013 -0.004916906 -0.9995203 -0.03075122 0.003681778 0.3083978 -0.9512521 0.003223121 -0.9995203 0.03075098 -0.003681778 0.4000781 -0.9164754 -0.003223001 -0.9564012 -0.2920107 0.005157589 0.6121382 -0.7907356 0.004917621 -0.9095062 -0.4156586 -0.005157828 -0.7277691 -0.6858124 0.003681361 -0.7339282 -0.6792222 0.002600908 0.7379449 -0.6748206 -0.00739479 0.895312 -0.4453728 0.007717192 -0.3832412 -0.923641 -0.003681004 -0.3748919 -0.9270649 -0.00260061 0.9654795 -0.2603647 -0.00771737 -0.07167369 -0.9974156 0.005007863 0.9995152 -0.03075098 0.004886209 0.9564107 0.2920165 0.002217054 0.9758929 0.2181958 -0.004868507 0.7339354 0.6792144 0.002600908 0.7627295 0.6467124 -0.002601265 0.3748964 0.9270631 -0.002599716 0.3832412 0.923641 -0.003682315 0.06609803 0.9977999 0.005157768 -0.06609803 0.9977999 -0.00515747 -0.3832412 0.923641 0.003681659 -0.3748964 0.9270631 0.002599716 -0.7339305 0.6792197 -0.002600431 -0.7277622 0.6858198 -0.003681361 -0.5124338 0.8587232 0.002493917 -0.491784 0.8707174 0 0.5124276 0.858721 -0.004038512 0.6631075 -0.7485128 -0.004153549 0.6630958 0.748523 0.004154324 0.4647734 -0.8854297 0 0.8051311 0.593097 0 0.5124206 -0.8587252 0.004037559 0.8229768 0.568066 -0.003209531 -0.5124261 -0.8587278 -0.002493977 -0.4917682 -0.8707262 0 -0.7907263 -0.612165 0.002494275 -0.8051292 -0.5930996 0 -0.9927133 -0.1205003 0 -0.9927117 0.1205143 0 -0.9927132 0.1205015 0 -0.8051223 0.593109 0 -0.7907305 0.6121594 -0.002492845 -0.4969791 0.8673958 0.02522945 -0.4994833 0.8663236 0 -0.9999926 0.0036394 -0.001296222 -0.9995065 -0.03141164 0 -0.9995066 -0.03141164 0 -0.9995065 0.03141164 0 -0.9995065 0.03141152 -5.40488e-7 0.2607764 0.9653987 -0.001025736 0.2722425 0.9608882 0.05077302 0.485692 0.8695802 0.08907067 0.4548181 0.8894649 -0.04464155 0.6714662 0.7319693 0.1155606 0.6278067 0.7745187 -0.07732886 0.8207989 0.5561721 0.1302378 0.7731004 0.6266594 -0.09804981 0.9768569 0.2138943 0 0.9266384 0.3515372 0.1332779 0.8852468 0.4526585 -0.1069512 0.9600635 0.259047 -0.1057016 0.9776753 0.209758 -0.01235842 0.1478217 0.988849 -0.01807326 0.1449594 0.9894352 -0.002199947 -0.4954168 0.8672063 -0.05015492 -0.2893691 0.9560276 0.04771572 -0.8121696 0.5826929 0.02914899 -0.8246182 0.5636873 -0.04755473 -0.8872838 -0.4592523 0.04260212 -0.8510497 -0.5230245 -0.04647529 -0.9778853 -0.2090659 -0.005644321 -0.9762568 -0.2160111 -0.01618665 -0.9985158 0.0234332 0.04916477 -0.9942981 0.09685629 -0.04461401 -0.9677039 0.2479713 0.04538166 -0.9442564 0.3252703 -0.05078667 -0.8784641 0.4685704 0.09350287 -0.6543051 -0.7560045 0.01850038 -0.7075672 -0.7066462 0 -0.6524864 -0.7578005 0 -0.7586506 -0.6514979 0 -0.707566 -0.7066472 0 -0.7572685 -0.6529436 -0.0144664 0.4200813 -0.9074698 0.005514502 0.4698004 -0.8800397 -0.06941026 0.2569457 -0.9663946 -0.007778286 0.2528796 -0.9673752 -0.01540249 -0.009790301 -0.9998433 0.01475 0.02661913 -0.9990317 -0.03502893 -0.2309143 -0.9723421 0.03506368 -0.1831859 -0.9830067 -0.01187604 -0.5238301 -0.8509129 0.03936254 -0.4631103 -0.8850856 -0.04639393 0.5695486 -0.8215546 0.02574324 0.5828878 -0.8119055 -0.03242576 0.9950919 -0.09892356 -0.002489268 0.9633077 -0.2644149 -0.04607564 0.8530211 -0.5196069 0.04862034 0.9952926 0.09689313 -0.002126514 0.9653059 0.2557452 -0.05271762 0.8557589 0.5150965 0.04850161 0.5810293 0.813462 0.02616482 0.5723834 0.8197036 -0.02152049 0.3937207 0.917876 0.04987806 0.470763 0.8794191 -0.07074075 0.1208745 0.9903873 0.06725043 0.2496791 0.9662752 -0.0630294 0.02326864 0.9986442 -0.04656672 -0.1949113 0.9805778 0.02184075 -0.2121771 0.9772294 -0.001946449 -0.5176523 0.8546785 0.03950703 -0.4655519 0.8841792 -0.03858095 -0.7578221 0.6524582 0.00200659 -0.707566 0.7066472 0 -0.7579999 0.6522547 0 -0.7075672 0.7066462 0 -0.6540688 0.7562705 0.01577711 -0.6525036 0.7577858 0 -0.8864634 0.4601503 0.04944229 -0.8506669 0.5241077 -0.04095196 -0.9833726 0.1815508 -0.004199624 -0.9764146 0.2110087 -0.0457161 -0.9987283 -0.02675133 0.04273653 -0.9915533 -0.1120665 -0.06529384 -0.9660707 -0.2504214 0.06321907 -0.9219951 -0.3828851 -0.05765557 -0.8804296 -0.4681974 0.07506662 -0.8182892 -0.5748026 -0.002189397 -0.8145138 -0.5794662 -0.02804166 -0.366857 -0.9302015 -0.01187431 -0.3698452 -0.9289918 -0.01374602 -0.2374436 -0.9714008 0.001108944 0.5061121 -0.8614922 -0.04101163 0.3666654 -0.929919 0.02841132 0.362033 -0.931736 0.02828735 0.8198598 -0.5724105 0.01327449 0.814777 -0.5792565 -0.02450191 0.8856089 0.4628596 0.03818064 0.8530148 0.5199508 -0.04491192 0.9772302 0.2121729 0.001949787 0.9805775 0.194912 -0.02184265 0.9986444 -0.02326369 0.04656291 0.9903861 -0.12088 -0.06725639 0.9662737 -0.2496816 0.06304311 0.9178748 -0.3937218 -0.04989165 0.8794188 -0.4707639 0.07074022 0.6547992 0.7556259 0.01635593 0.7122474 0.7019285 0 0.6532794 0.7571171 0 0.7685679 0.6397683 0 0.712247 0.701929 0 0.7728456 0.631231 0.06524741 0.979077 0.2015057 -0.02834922 0.9626036 0.261123 0.07217574 0.8744811 0.4801923 -0.06854408 0.9999855 0.002908289 0.004556298 0.9994965 0.005610942 -0.03123092 0.08962333 0.995032 0.04334825 0.3258507 0.944469 -0.04242259 0.6447987 0.7637106 0.03131979 0.7743819 0.6316127 -0.03739315 0.9295068 0.3666698 0.03962814 -0.1792407 0.9831197 -0.03672307 -0.997979 -0.06212717 0.01334929 -0.9981137 -0.06139391 1.03285e-6 -0.9995066 0.03141129 -4.94161e-7 -0.2145076 -0.9767223 0 -0.2101328 -0.9775917 -0.01260089 -0.3444169 -0.9320109 0.1128401 -0.2587931 -0.9600661 -0.1062978 -0.5358331 -0.8365433 0.1143602 -0.4526966 -0.8853192 -0.1061871 -0.702425 -0.7024245 0.1148872 -0.6260648 -0.7723662 -0.107207 -0.836543 -0.5358335 0.1143603 -0.7723692 -0.6260631 -0.1071965 -0.9320125 -0.3444179 0.1128233 -0.8853158 -0.4527008 -0.1061977 -0.960064 -0.2589946 -0.1058253 -0.9768298 -0.2132042 -0.01864516 3.50383e-7 0 -1 -8.39287e-7 0 -1 -1.75176e-7 0 -1 -1.40747e-7 0 -1 5.56308e-4 0.003219008 0.9999948 -6.17076e-4 0.003566086 0.9999935 0.9767196 -0.2145206 0 0.977681 -0.2096263 -0.01402771 0.9320125 -0.3444179 0.1128233 0.9600523 -0.2597075 -0.1041709 0.836543 -0.5358335 0.1143603 0.885316 -0.4527009 -0.106196 0.702425 -0.7024245 0.1148872 0.7723692 -0.6260631 -0.1071965 0.5358331 -0.8365433 0.1143602 0.6260648 -0.7723662 -0.107207 0.213895 -0.9768567 0 0.3444169 -0.9320109 0.1128401 0.4526966 -0.8853192 -0.1061871 0.2590473 -0.9600628 -0.1057078 0.2097672 -0.9776732 -0.01235926 1.75176e-7 0 -1 -2.29361e-7 0 -1 6.29465e-7 0 -1 -3.50383e-7 0 -1 -1.89481e-7 0 -1 -0.002895057 4.85541e-4 0.9999957 -0.003197669 -5.36408e-4 0.9999948 0 0 -1 0 0 -1 -3.3795e-6 2.65457e-6 -1 9.40444e-6 9.97958e-6 -1 0 0 -1 1.80112e-5 1.91126e-5 -1 0 0 -1 1.28331e-5 2.80802e-5 -1 -5.1825e-7 6.61216e-6 -1 -5.83011e-6 1.06459e-5 -1 3.81767e-6 -9.93554e-6 -1 0 0 -1 1.3549e-5 0 -1 -1.89845e-6 3.29274e-6 -1 -2.41279e-5 -7.67843e-6 -1 -5.44829e-5 -3.66144e-5 -1 0 0 -1 2.47471e-6 -2.67403e-6 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 1.45657e-5 -9.09967e-6 -1 -2.15174e-5 8.92794e-6 -1 0 0 -1 6.61717e-6 -1.10888e-5 -1 1.43461e-5 -1.06331e-5 -1 -1.08506e-4 -1.60971e-4 -1 3.07092e-6 -2.26216e-6 -1 3.17729e-7 -8.19669e-6 -1 -8.21932e-6 2.692e-5 -1 0 0 -1 -1.32483e-4 8.77471e-6 -1 2.76893e-7 -1.08724e-5 -1 2.22544e-5 2.3177e-6 -1 0 0 -1 4.7347e-7 1.53935e-5 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 -5.82859e-5 1.07243e-4 -1 -8.75654e-5 2.66291e-4 -1 -1.5025e-5 4.20153e-6 -1 0 0 -1 1.4257e-5 5.76534e-6 -1 1.33689e-5 2.88779e-5 -1 0 0 -1 0 0 -1 5.1887e-6 1.13535e-5 -1 0 0 -1 1.73765e-5 1.98043e-5 -1 -2.034e-6 2.19779e-6 -1 0 0 -1 0 0 -1 -1.75113e-5 -1.85823e-5 -1 0 0 -1 0 0 -1 -1.90841e-6 -3.4764e-5 -1 -3.8006e-4 -4.67787e-5 -1 4.74742e-6 -4.97472e-6 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 -1.47022e-6 5.6242e-6 -1 -2.89059e-7 1.08486e-5 -1 -8.2409e-5 -2.0862e-4 -1 -1.544e-5 -6.50634e-6 -1 0 0 -1 -3.92437e-6 -2.3507e-6 -1 -1.98073e-6 -7.69508e-7 -1 0 0 -1 -1.54539e-5 -6.24936e-6 -1 -2.64475e-7 6.82282e-6 -1 -2.55375e-6 1.88121e-6 -1 0 0 -1 0 0 -1 5.93952e-7 -9.95324e-7 -1 -2.76839e-6 -3.6821e-5 -1 0 0 -1 0 0 -1 0 0 -1 1.14797e-6 -9.21815e-7 -1 -1.83282e-5 -2.43774e-4 -1 2.46194e-7 -9.98928e-7 -1 0 0 -1 0 0 -1 1.61187e-4 -1.06777e-5 -1 0 0 -1 0 0 -1 0 0 -1 1.4316e-4 -5.94007e-5 -1 0 0 -1 0 0 -1 0 0 -1 4.70128e-7 -7.5219e-7 -1 0 0 -1 0 0 -1 0 0 -1 -2.21974e-5 -1.57626e-6 -1 1.47713e-4 3.0794e-5 -1 -2.04006e-5 -8.83511e-6 -1 -1.23631e-5 -2.70518e-5 -1 0 0 -1 0 0 -1 0 0 -1 9.06982e-7 -1.52112e-5 -1 1.86027e-5 -9.2538e-6 -1 0 0 -1 -1.9453e-5 1.33725e-4 -1 1.0838e-5 -1.40003e-5 -1 -2.26533e-6 -4.21542e-5 -1 0 0 -1 0 0 -1 0 0 -1 5.00284e-5 2.6215e-5 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 5.23014e-4 -1.81109e-4 -1 -7.20139e-4 2.94521e-4 -0.9999998 -6.43415e-6 -7.01239e-6 -1 -1.42147e-5 4.37163e-7 -1 0 0 -1 0 0 -1 6.66225e-6 8.88373e-7 -1 0 0 -1 1.26105e-5 -1.98937e-7 -1 1.67958e-4 -2.48316e-4 -1 2.97059e-6 2.18829e-6 -1 8.36707e-7 1.7131e-4 -1 -1.1405e-5 -3.48218e-6 -1 0 0 -1 0 0 -1 0 0 -1 -6.36406e-6 -7.06378e-6 -1 -6.50089e-6 -2.46571e-6 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 -2.24098e-7 0 -1 -3.01824e-5 5.57804e-5 -1 -1.83717e-7 -1.70023e-7 -1 0 0 -1 -0.9871038 -0.1567587 0.0324459 -0.988509 -0.1507961 0.01051586 0.9893556 0.1442037 0.01951861 0.9888245 0.1490797 0.001257359 0.9890285 -0.1456419 0.02472281 0.9882411 -0.1528845 -0.002429783 0.1447367 -0.9893878 0.01277673 0.1476786 -0.9890342 0.001573681 -0.1420087 -0.9898235 -0.009121358 -0.1460862 -0.9892565 0.00551784 -1.24448e-6 0 -1 8.04487e-7 0 -1 -6.0193e-7 0 -1 0.2952978 -0.9554053 0 0.2926302 -0.9562258 -2.75122e-4 0.2918092 -0.9564669 -0.004306435 0.2923846 -0.9563009 0 -0.5947171 -0.8039351 0 -0.5947167 -0.8039354 0 -0.5947171 0.8039351 0 -0.5947167 0.8039354 0 0.2918879 0.9564526 0 0.2926303 0.9562253 -8.30161e-4 0.3006644 0.9537301 0 0.2915156 0.9565621 -0.002788245 1 0 0 -1.36027e-6 0 1 2.67531e-7 0 1 1.36059e-6 0 1 0.3046743 0.9524526 -0.002783894 0.3006616 0.953731 0 -1.56911e-5 0 1 8.05313e-6 0 1 0.3015069 -0.953464 0 0.2952919 -0.9553974 -0.00430566 + + + + + + + + + + + + + + +

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

+
+
+
+ + + + -0.1486946 0.06434589 0.1635 -0.1466001 0.06898474 0.02199995 -0.1486946 0.06434589 0.02199995 -0.1466001 0.06898474 0.1635 -0.1486946 0.06434589 0.197 -0.1466001 0.06898474 0.197 -0.1506423 0.0596435 0.1635 -0.1506423 0.0596435 0.02199995 0.121533 0.1071457 0.02199995 -0.1461027 0.06999999 0.02199995 0.1181074 0.1109102 0.02199995 0.1071457 0.121533 0.02199995 0.1109102 0.1181074 0.02199995 0.1145654 0.1145654 0.02199995 -0.09106874 -0.1340036 0.02199995 -0.09523296 -0.1310769 0.02199995 -0.1347056 -0.08999997 0.02199995 -0.09930318 -0.1280209 0.02199995 -0.1032754 -0.1248385 0.02199995 -0.1071457 -0.121533 0.02199995 -0.1109102 -0.1181074 0.02199995 -0.1145654 -0.1145654 0.02199995 -0.1181074 -0.1109102 0.02199995 -0.121533 -0.1071457 0.02199995 -0.1248385 -0.1032754 0.02199995 -0.1280209 -0.09930318 0.02199995 -0.1310769 -0.09523296 0.02199995 -0.1340036 -0.09106874 0.02199995 -0.08681464 -0.136798 0.02199995 -0.08247488 -0.1394574 0.02199995 -0.136798 -0.08681464 0.02199995 -0.1394574 -0.08247488 0.02199995 -0.07805371 -0.1419792 0.02199995 -0.1419792 -0.07805371 0.02199995 -0.07355552 -0.1443608 0.02199995 -0.1443608 -0.07355552 0.02199995 -0.06898474 -0.1466001 0.02199995 -0.1466001 -0.06898474 0.02199995 -0.06434589 -0.1486946 0.02199995 -0.1486946 -0.06434589 0.02199995 -0.0596435 -0.1506423 0.02199995 -0.05488228 -0.1524415 0.02199995 -0.05006688 -0.1540902 0.02199995 -0.04520213 -0.1555868 0.02199995 -0.04029268 -0.1569298 0.02199995 -0.1578007 -0.03666484 0.02199995 -0.1506423 -0.0596435 0.02199995 -0.1524415 -0.05488228 0.02199995 -0.1540902 -0.05006688 0.02199995 -0.1555868 -0.04520213 0.02199995 -0.1569298 -0.04029268 0.02199995 -0.03534352 -0.158118 0.02199995 -0.0303595 -0.1591502 0.02199995 -0.0253455 -0.1600252 0.02199995 -0.02030646 -0.1607424 0.02199995 -0.0152474 -0.1613008 0.02199995 -0.01017332 -0.1617003 0.02199995 -0.005089163 -0.16194 0.02199995 0 -0.16202 0.02199995 0.005089163 -0.16194 0.02199995 0.01017332 -0.1617003 0.02199995 0.0152474 -0.1613008 0.02199995 0.02030646 -0.1607424 0.02199995 0.0253455 -0.1600252 0.02199995 0.0303595 -0.1591502 0.02199995 0.03534352 -0.158118 0.02199995 -0.1578007 0.03666484 0.02199995 0.04029268 -0.1569298 0.02199995 0.04520213 -0.1555868 0.02199995 -0.1569298 0.04029268 0.02199995 -0.1555868 0.04520213 0.02199995 0.05006688 -0.1540902 0.02199995 -0.1540902 0.05006688 0.02199995 0.05488228 -0.1524415 0.02199995 -0.1524415 0.05488228 0.02199995 0.0596435 -0.1506423 0.02199995 0.06434589 -0.1486946 0.02199995 0.06898474 -0.1466001 0.02199995 0.07355552 -0.1443608 0.02199995 0.07805371 -0.1419792 0.02199995 -0.1443608 0.07355552 0.02199995 -0.1419792 0.07805371 0.02199995 0.08247488 -0.1394574 0.02199995 -0.1394574 0.08247488 0.02199995 0.08681464 -0.136798 0.02199995 -0.136798 0.08681464 0.02199995 0.09106874 -0.1340036 0.02199995 -0.1340036 0.09106874 0.02199995 0.09523296 -0.1310769 0.02199995 -0.1310769 0.09523296 0.02199995 0.09930318 -0.1280209 0.02199995 -0.1280209 0.09930318 0.02199995 0.1032754 -0.1248385 0.02199995 -0.1248385 0.1032754 0.02199995 0.1071457 -0.121533 0.02199995 -0.121533 0.1071457 0.02199995 0.1109102 -0.1181074 0.02199995 -0.1181074 0.1109102 0.02199995 0.1145654 -0.1145654 0.02199995 -0.1145654 0.1145654 0.02199995 0.1181074 -0.1109102 0.02199995 -0.1109102 0.1181074 0.02199995 0.121533 -0.1071457 0.02199995 -0.1071457 0.121533 0.02199995 0.1248385 -0.1032754 0.02199995 -0.1032754 0.1248385 0.02199995 0.1280209 -0.09930318 0.02199995 -0.09930318 0.1280209 0.02199995 0.1310769 -0.09523296 0.02199995 -0.09523296 0.1310769 0.02199995 0.1340036 -0.09106874 0.02199995 -0.09106874 0.1340036 0.02199995 0.136798 -0.08681464 0.02199995 -0.08681464 0.136798 0.02199995 0.1394574 -0.08247488 0.02199995 -0.08247488 0.1394574 0.02199995 0.1419792 -0.07805371 0.02199995 -0.07805371 0.1419792 0.02199995 0.1443608 -0.07355552 0.02199995 -0.07355552 0.1443608 0.02199995 0.1466001 -0.06898474 0.02199995 -0.06898474 0.1466001 0.02199995 0.1486946 -0.06434589 0.02199995 -0.06434589 0.1486946 0.02199995 0.1506423 -0.0596435 0.02199995 -0.0596435 0.1506423 0.02199995 0.1524415 -0.05488228 0.02199995 -0.05488228 0.1524415 0.02199995 0.1540902 -0.05006688 0.02199995 -0.05006688 0.1540902 0.02199995 0.1555868 -0.04520213 0.02199995 -0.04520213 0.1555868 0.02199995 0.1569298 -0.04029268 0.02199995 -0.04029268 0.1569298 0.02199995 0.158118 -0.03534352 0.02199995 -0.03534352 0.158118 0.02199995 0.1591502 -0.0303595 0.02199995 -0.0303595 0.1591502 0.02199995 0.1600252 -0.0253455 0.02199995 -0.0253455 0.1600252 0.02199995 0.1607424 -0.02030646 0.02199995 -0.02030646 0.1607424 0.02199995 0.1613008 -0.0152474 0.02199995 -0.0152474 0.1613008 0.02199995 0.1617003 -0.01017332 0.02199995 -0.01017332 0.1617003 0.02199995 0.16194 -0.005089163 0.02199995 -0.005089163 0.16194 0.02199995 0 0.16202 0.02199995 0.16202 0 0.02199995 0.16194 0.005089163 0.02199995 0.005089163 0.16194 0.02199995 0.01017332 0.1617003 0.02199995 0.1617003 0.01017332 0.02199995 0.0152474 0.1613008 0.02199995 0.1613008 0.0152474 0.02199995 0.1607424 0.02030646 0.02199995 0.02030646 0.1607424 0.02199995 0.1600252 0.0253455 0.02199995 0.0253455 0.1600252 0.02199995 0.1591502 0.0303595 0.02199995 0.0303595 0.1591502 0.02199995 0.03534352 0.158118 0.02199995 0.158118 0.03534352 0.02199995 0.04029268 0.1569298 0.02199995 0.1569298 0.04029268 0.02199995 0.1555868 0.04520213 0.02199995 0.04520213 0.1555868 0.02199995 0.05006688 0.1540902 0.02199995 0.1540902 0.05006688 0.02199995 0.1524415 0.05488228 0.02199995 0.05488228 0.1524415 0.02199995 0.1506423 0.0596435 0.02199995 0.0596435 0.1506423 0.02199995 0.06434589 0.1486946 0.02199995 0.1486946 0.06434589 0.02199995 0.06898474 0.1466001 0.02199995 0.1466001 0.06898474 0.02199995 0.1443608 0.07355552 0.02199995 0.07355552 0.1443608 0.02199995 0.1419792 0.07805371 0.02199995 0.07805371 0.1419792 0.02199995 0.1394574 0.08247488 0.02199995 0.08247488 0.1394574 0.02199995 0.08681464 0.136798 0.02199995 0.136798 0.08681464 0.02199995 0.1340036 0.09106874 0.02199995 0.09106874 0.1340036 0.02199995 0.09523296 0.1310769 0.02199995 0.1310769 0.09523296 0.02199995 0.1280209 0.09930318 0.02199995 0.09930318 0.1280209 0.02199995 0.1032754 0.1248385 0.02199995 0.1248385 0.1032754 0.02199995 -0.1461027 0.06999999 0.1635 -0.1506423 0.0596435 0.197 -0.07355552 -0.1443608 0.197 -0.06898474 -0.1466001 0.197 -0.07505387 -0.1473014 0.197 -0.0461229 0.1587561 0.197 -0.04029268 0.1569298 0.197 -0.04520213 0.1555868 0.197 0.1448714 0.07964366 0.197 0.1473014 0.07505387 0.197 0.1443608 0.07355552 0.197 -0.05006688 0.1540902 0.197 -0.04111349 0.1601266 0.197 -0.1587561 0.0461229 0.197 -0.1555868 0.04520213 0.197 -0.1601266 0.04111349 0.197 0.1419792 0.07805371 0.197 -0.07805371 -0.1419792 0.197 -0.07964366 -0.1448714 0.197 -0.05108678 0.157229 0.197 -0.05488228 0.1524415 0.197 0.1422982 0.0841549 0.197 -0.157229 0.05108678 0.197 -0.1524415 0.05488228 0.197 -0.1540902 0.05006688 0.197 -0.0841549 -0.1422982 0.197 0.1394574 0.08247488 0.197 -0.05600029 0.1555468 0.197 -0.08247488 -0.1394574 0.197 -0.1555468 0.05600029 0.197 -0.06085848 0.153711 0.197 -0.0596435 0.1506423 0.197 -0.06434589 0.1486946 0.197 0.136798 0.08681464 0.197 0.1395846 0.08858305 0.197 -0.08681464 -0.136798 0.197 -0.08858305 -0.1395846 0.197 0.1145654 -0.1145654 0.197 0.1205134 -0.1131696 0.197 0.1168992 -0.1168992 0.197 -0.153711 0.06085848 0.197 0.1181074 -0.1109102 0.197 0.1240087 -0.1093283 0.197 0.1340036 0.09106874 0.197 -0.0656566 0.1517236 0.197 0.1109102 -0.1181074 0.197 0.1131696 -0.1205134 0.197 -0.06898474 0.1466001 0.197 0.1367332 0.09292382 0.197 -0.09106874 -0.1340036 0.197 -0.1517236 0.0656566 0.197 -0.09292382 -0.1367332 0.197 0.1071457 -0.121533 0.197 0.1093283 -0.1240087 0.197 0.121533 -0.1071457 0.197 0.1273816 -0.1053792 0.197 -0.1495864 0.07038998 0.197 0.1310769 0.09523296 0.197 0.133747 0.09717285 0.197 -0.07038998 0.1495864 0.197 -0.09523296 -0.1310769 0.197 -0.09717285 -0.133747 0.197 -0.101326 -0.1306287 0.197 0.1248385 -0.1032754 0.197 0.1280209 0.09930318 0.197 0.1306287 0.101326 0.197 0.1032754 -0.1248385 0.197 0.1053792 -0.1273816 0.197 -0.09930318 -0.1280209 0.197 -0.07505387 0.1473014 0.197 -0.07355552 0.1443608 0.197 0.1280209 -0.09930318 0.197 0.1306287 -0.101326 0.197 -0.07805371 0.1419792 0.197 -0.1473014 0.07505387 0.197 0.1273816 0.1053792 0.197 -0.1053792 -0.1273816 0.197 -0.1419792 0.07805371 0.197 -0.1443608 0.07355552 0.197 0.09930318 -0.1280209 0.197 0.101326 -0.1306287 0.197 0.1248385 0.1032754 0.197 -0.1448714 0.07964366 0.197 -0.1032754 -0.1248385 0.197 -0.1394574 0.08247488 0.197 -0.07964366 0.1448714 0.197 0.1240087 0.1093283 0.197 0.1310769 -0.09523296 0.197 0.1367332 -0.09292382 0.197 0.133747 -0.09717285 0.197 0.09523296 -0.1310769 0.197 0.09717285 -0.133747 0.197 0.121533 0.1071457 0.197 -0.1071457 -0.121533 0.197 0.1340036 -0.09106874 0.197 -0.1093283 -0.1240087 0.197 -0.0841549 0.1422982 0.197 0.09106874 -0.1340036 0.197 0.09292382 -0.1367332 0.197 -0.08247488 0.1394574 0.197 -0.08681464 0.136798 0.197 0.1205134 0.1131696 0.197 -0.1422982 0.0841549 0.197 0.1181074 0.1109102 0.197 -0.1109102 -0.1181074 0.197 -0.1131696 -0.1205134 0.197 0.136798 -0.08681464 0.197 0.1168992 0.1168992 0.197 0.1422982 -0.0841549 0.197 0.1395846 -0.08858305 0.197 0.08681464 -0.136798 0.197 0.08858305 -0.1395846 0.197 0.1145654 0.1145654 0.197 -0.1395846 0.08858305 0.197 -0.1145654 -0.1145654 0.197 -0.136798 0.08681464 0.197 -0.1168992 -0.1168992 0.197 -0.08858305 0.1395846 0.197 -0.09106874 0.1340036 0.197 0.1394574 -0.08247488 0.197 -0.1181074 -0.1109102 0.197 0.1131696 0.1205134 0.197 0.1109102 0.1181074 0.197 0.08247488 -0.1394574 0.197 0.0841549 -0.1422982 0.197 0.07964366 -0.1448714 0.197 -0.1205134 -0.1131696 0.197 0.1419792 -0.07805371 0.197 0.1071457 0.121533 0.197 0.1473014 -0.07505387 0.197 0.1448714 -0.07964366 0.197 -0.121533 -0.1071457 0.197 -0.09292382 0.1367332 0.197 -0.09523296 0.1310769 0.197 0.1093283 0.1240087 0.197 0.07805371 -0.1419792 0.197 -0.1240087 -0.1093283 0.197 -0.1367332 0.09292382 0.197 -0.1310769 0.09523296 0.197 -0.1340036 0.09106874 0.197 0.1032754 0.1248385 0.197 0.1443608 -0.07355552 0.197 -0.1248385 -0.1032754 0.197 0.07355552 -0.1443608 0.197 0.07505387 -0.1473014 0.197 -0.133747 0.09717285 0.197 0.1053792 0.1273816 0.197 -0.09717285 0.133747 0.197 -0.09930318 0.1280209 0.197 -0.1273816 -0.1053792 0.197 0.09930318 0.1280209 0.197 -0.1280209 -0.09930318 0.197 0.1466001 -0.06898474 0.197 -0.101326 0.1306287 0.197 0.101326 0.1306287 0.197 0.1517236 -0.0656566 0.197 0.1495864 -0.07038998 0.197 -0.1306287 -0.101326 0.197 0.06898474 -0.1466001 0.197 0.07038998 -0.1495864 0.197 -0.1306287 0.101326 0.197 -0.1248385 0.1032754 0.197 -0.1280209 0.09930318 0.197 0.09523296 0.1310769 0.197 -0.1053792 0.1273816 0.197 -0.1032754 0.1248385 0.197 0.09717285 0.133747 0.197 -0.133747 -0.09717285 0.197 -0.1273816 0.1053792 0.197 0.1486946 -0.06434589 0.197 -0.1310769 -0.09523296 0.197 -0.121533 0.1071457 0.197 -0.1093283 0.1240087 0.197 -0.1071457 0.121533 0.197 0.06434589 -0.1486946 0.197 0.0656566 -0.1517236 0.197 -0.1240087 0.1093283 0.197 -0.1340036 -0.09106874 0.197 -0.1181074 0.1109102 0.197 0.09292382 0.1367332 0.197 -0.1205134 0.1131696 0.197 0.09106874 0.1340036 0.197 -0.1367332 -0.09292382 0.197 0.1506423 -0.0596435 0.197 -0.1131696 0.1205134 0.197 -0.1109102 0.1181074 0.197 -0.1145654 0.1145654 0.197 0.1555468 -0.05600029 0.197 0.153711 -0.06085848 0.197 0.0596435 -0.1506423 0.197 0.06085848 -0.153711 0.197 0.05600029 -0.1555468 0.197 -0.1168992 0.1168992 0.197 0.08858305 0.1395846 0.197 0.08681464 0.136798 0.197 -0.1395846 -0.08858305 0.197 -0.136798 -0.08681464 0.197 0.1524415 -0.05488228 0.197 0.157229 -0.05108678 0.197 0.0841549 0.1422982 0.197 0.08247488 0.1394574 0.197 0.05488228 -0.1524415 0.197 -0.1422982 -0.0841549 0.197 -0.1394574 -0.08247488 0.197 0.1540902 -0.05006688 0.197 0.07964366 0.1448714 0.197 0.07805371 0.1419792 0.197 0.1587561 -0.0461229 0.197 -0.1448714 -0.07964366 0.197 -0.1419792 -0.07805371 0.197 0.05006688 -0.1540902 0.197 0.05108678 -0.157229 0.197 0.0461229 -0.1587561 0.197 0.1555868 -0.04520213 0.197 0.1601266 -0.04111349 0.197 0.07505387 0.1473014 0.197 0.07355552 0.1443608 0.197 0.04520213 -0.1555868 0.197 0.04111349 -0.1601266 0.197 -0.1473014 -0.07505387 0.197 -0.1443608 -0.07355552 0.197 -0.1466001 -0.06898474 0.197 0.07038998 0.1495864 0.197 0.06898474 0.1466001 0.197 0.1569298 -0.04029268 0.197 0.1613389 -0.03606349 0.197 0.04029268 -0.1569298 0.197 -0.1495864 -0.07038998 0.197 0.158118 -0.03534352 0.197 0.03534352 -0.158118 0.197 0.03606349 -0.1613389 0.197 -0.1486946 -0.06434589 0.197 0.1623921 -0.0309779 0.197 0.0656566 0.1517236 0.197 0.06434589 0.1486946 0.197 0.0309779 -0.1623921 0.197 -0.1517236 -0.0656566 0.197 0.1591502 -0.0303595 0.197 0.0596435 0.1506423 0.197 0.0303595 -0.1591502 0.197 -0.1506423 -0.0596435 0.197 0.06085848 0.153711 0.197 -0.153711 -0.06085848 0.197 0.1600252 -0.0253455 0.197 0.163285 -0.02586179 0.197 -0.1524415 -0.05488228 0.197 0.0253455 -0.1600252 0.197 0.02586179 -0.163285 0.197 0.05600029 0.1555468 0.197 0.05488228 0.1524415 0.197 0.1640168 -0.02072012 0.197 -0.1555468 -0.05600029 0.197 0.02072012 -0.1640168 0.197 0.1607424 -0.02030646 0.197 0.05006688 0.1540902 0.197 -0.1540902 -0.05006688 0.197 0.05108678 0.157229 0.197 0.02030646 -0.1607424 0.197 -0.157229 -0.05108678 0.197 0.1645867 -0.015558 0.197 0.1613008 -0.0152474 0.197 0.0461229 0.1587561 0.197 0.04520213 0.1555868 0.197 0.0152474 -0.1613008 0.197 -0.1587561 -0.0461229 0.197 -0.1555868 -0.04520213 0.197 0.015558 -0.1645867 0.197 0.0103805 -0.1649942 0.197 0.1617003 -0.01017332 0.197 0.04111349 0.1601266 0.197 0.04029268 0.1569298 0.197 0.1649942 -0.0103805 0.197 0.01017332 -0.1617003 0.197 -0.1601266 -0.04111349 0.197 -0.1569298 -0.04029268 0.197 0.1652387 -0.005192816 0.197 0.005192816 -0.1652387 0.197 0.16194 -0.005089163 0.197 0.005089163 -0.16194 0.197 0.16202 0 0.197 0.1653203 0 0.197 0 -0.16202 0.197 0 -0.1653203 0.197 0.1652387 0.005192816 0.197 -0.005192816 -0.1652387 0.197 0.16194 0.005089163 0.197 -0.005089163 -0.16194 0.197 0.1617003 0.01017332 0.197 0.1649942 0.0103805 0.197 -0.01017332 -0.1617003 0.197 -0.0103805 -0.1649942 0.197 0.1645867 0.015558 0.197 -0.015558 -0.1645867 0.197 0.1613008 0.0152474 0.197 -0.0152474 -0.1613008 0.197 0.1607424 0.02030646 0.197 0.1640168 0.02072012 0.197 -0.02030646 -0.1607424 0.197 -0.02072012 -0.1640168 0.197 0.163285 0.02586179 0.197 0.1600252 0.0253455 0.197 -0.1609623 -0.03763234 0.197 -0.1578007 -0.03666484 0.197 -0.0253455 -0.1600252 0.197 -0.02586179 -0.163285 0.197 0.03606349 0.1613389 0.197 0.1623921 0.0309779 0.197 0.03534352 0.158118 0.197 -0.0309779 -0.1623921 0.197 0.1591502 0.0303595 0.197 0.0309779 0.1623921 0.197 0.0303595 0.1591502 0.197 0.0253455 0.1600252 0.197 -0.0303595 -0.1591502 0.197 0.02586179 0.163285 0.197 0.02030646 0.1607424 0.197 0.02072012 0.1640168 0.197 0.158118 0.03534352 0.197 0.015558 0.1645867 0.197 0.1613389 0.03606349 0.197 0.0152474 0.1613008 0.197 0.01017332 0.1617003 0.197 -0.03534352 -0.158118 0.197 -0.03606349 -0.1613389 0.197 0.0103805 0.1649942 0.197 -0.04111349 -0.1601266 0.197 0.005192816 0.1652387 0.197 0.005089163 0.16194 0.197 0.1569298 0.04029268 0.197 0.1601266 0.04111349 0.197 0 0.16202 0.197 -0.04029268 -0.1569298 0.197 0 0.1653203 0.197 0.1587561 0.0461229 0.197 -0.0461229 -0.1587561 0.197 -0.005192816 0.1652387 0.197 -0.005089163 0.16194 0.197 0.1555868 0.04520213 0.197 -0.01017332 0.1617003 0.197 -0.0103805 0.1649942 0.197 -0.04520213 -0.1555868 0.197 -0.015558 0.1645867 0.197 -0.0152474 0.1613008 0.197 0.1540902 0.05006688 0.197 -0.02030646 0.1607424 0.197 -0.02072012 0.1640168 0.197 0.157229 0.05108678 0.197 -0.05006688 -0.1540902 0.197 -0.05108678 -0.157229 0.197 -0.0253455 0.1600252 0.197 -0.02586179 0.163285 0.197 -0.05600029 -0.1555468 0.197 -0.0309779 0.1623921 0.197 -0.0303595 0.1591502 0.197 0.1524415 0.05488228 0.197 0.1555468 0.05600029 0.197 -0.03534352 0.158118 0.197 -0.05488228 -0.1524415 0.197 0.153711 0.06085848 0.197 0.1506423 0.0596435 0.197 -0.0596435 -0.1506423 0.197 -0.06085848 -0.153711 0.197 0.1486946 0.06434589 0.197 0.1517236 0.0656566 0.197 -0.06434589 -0.1486946 0.197 -0.0656566 -0.1517236 0.197 0.1466001 0.06898474 0.197 0.1495864 0.07038998 0.197 -0.03606349 0.1613389 0.197 -0.07038998 -0.1495864 0.197 -0.1609623 0.03763234 0.197 -0.1569298 0.04029268 0.197 -0.1578007 0.03666484 0.197 -0.1524415 0.05488228 0.1635 -0.1347056 -0.08999997 0.1635 -0.136798 -0.08681464 0.1635 -0.1394574 -0.08247488 0.1635 -0.1419792 -0.07805371 0.1635 -0.1443608 -0.07355552 0.1635 -0.1466001 -0.06898474 0.1635 -0.1486946 -0.06434589 0.1635 -0.1506423 -0.0596435 0.1635 -0.1524415 -0.05488228 0.1635 -0.1540902 -0.05006688 0.1635 -0.1555868 -0.04520213 0.1635 -0.1569298 -0.04029268 0.1635 -0.1578007 -0.03666484 0.1635 -0.1578007 0.03666484 0.1635 -0.1569298 0.04029268 0.1635 -0.1555868 0.04520213 0.1635 -0.1540902 0.05006688 0.1635 -0.1609623 -0.03763234 0.1635 -0.1609623 0.03763234 0.1635 -0.1609623 0.03763234 0.202 -0.1613389 0.03606349 0.202 -0.1613389 0.03606349 0.225 -0.1601266 0.04111349 0.225 -0.1587561 0.0461229 0.225 -0.157229 0.05108678 0.225 -0.1555468 0.05600029 0.225 -0.153711 0.06085848 0.225 -0.1517236 0.0656566 0.225 -0.1495864 0.07038998 0.225 -0.1473014 0.07505387 0.225 -0.1448714 0.07964366 0.225 -0.1422982 0.0841549 0.225 -0.1395846 0.08858305 0.225 -0.1367332 0.09292382 0.225 -0.133747 0.09717285 0.225 -0.1306287 0.101326 0.225 -0.1273816 0.1053792 0.225 -0.1240087 0.1093283 0.225 -0.1205134 0.1131696 0.225 -0.1168992 0.1168992 0.225 -0.1131696 0.1205134 0.225 -0.1093283 0.1240087 0.225 -0.1053792 0.1273816 0.225 -0.101326 0.1306287 0.225 -0.09717285 0.133747 0.225 -0.09292382 0.1367332 0.225 -0.08858305 0.1395846 0.225 -0.0841549 0.1422982 0.225 -0.07964366 0.1448714 0.225 -0.07505387 0.1473014 0.225 -0.07038998 0.1495864 0.225 -0.0656566 0.1517236 0.225 -0.06085848 0.153711 0.225 -0.05600029 0.1555468 0.225 -0.05108678 0.157229 0.225 -0.0461229 0.1587561 0.225 -0.04111349 0.1601266 0.225 -0.03606349 0.1613389 0.225 -0.0309779 0.1623921 0.225 -0.02586179 0.163285 0.225 -0.02072012 0.1640168 0.225 -0.015558 0.1645867 0.225 -0.0103805 0.1649942 0.225 -0.005192816 0.1652387 0.225 0 0.1653203 0.225 0.005192816 0.1652387 0.225 0.0103805 0.1649942 0.225 0.015558 0.1645867 0.225 0.02072012 0.1640168 0.225 0.02586179 0.163285 0.225 0.0309779 0.1623921 0.225 0.03606349 0.1613389 0.225 0.04111349 0.1601266 0.225 0.0461229 0.1587561 0.225 0.05108678 0.157229 0.225 0.05600029 0.1555468 0.225 0.06085848 0.153711 0.225 0.0656566 0.1517236 0.225 0.07038998 0.1495864 0.225 0.07505387 0.1473014 0.225 0.07964366 0.1448714 0.225 0.0841549 0.1422982 0.225 0.08858305 0.1395846 0.225 0.09292382 0.1367332 0.225 0.09717285 0.133747 0.225 0.101326 0.1306287 0.225 0.1053792 0.1273816 0.225 0.1093283 0.1240087 0.225 0.1131696 0.1205134 0.225 0.1168992 0.1168992 0.225 0.1205134 0.1131696 0.225 0.1240087 0.1093283 0.225 0.1273816 0.1053792 0.225 0.1306287 0.101326 0.225 0.133747 0.09717285 0.225 0.1367332 0.09292382 0.225 0.1395846 0.08858305 0.225 0.1422982 0.0841549 0.225 0.1448714 0.07964366 0.225 0.1473014 0.07505387 0.225 0.1495864 0.07038998 0.225 0.1517236 0.0656566 0.225 0.153711 0.06085848 0.225 0.1555468 0.05600029 0.225 0.157229 0.05108678 0.225 0.1587561 0.0461229 0.225 0.1601266 0.04111349 0.225 0.1613389 0.03606349 0.225 0.1623921 0.0309779 0.225 0.163285 0.02586179 0.225 0.1640168 0.02072012 0.225 0.1645867 0.015558 0.225 0.1649942 0.0103805 0.225 0.1652387 0.005192816 0.225 0.1653203 0 0.225 0.1652387 -0.005192816 0.225 0.1649942 -0.0103805 0.225 0.1645867 -0.015558 0.225 0.1640168 -0.02072012 0.225 0.163285 -0.02586179 0.225 0.1623921 -0.0309779 0.225 0.1613389 -0.03606349 0.225 0.1601266 -0.04111349 0.225 0.1587561 -0.0461229 0.225 0.157229 -0.05108678 0.225 0.1555468 -0.05600029 0.225 0.153711 -0.06085848 0.225 0.1517236 -0.0656566 0.225 0.1495864 -0.07038998 0.225 0.1473014 -0.07505387 0.225 0.1448714 -0.07964366 0.225 0.1422982 -0.0841549 0.225 0.1395846 -0.08858305 0.225 0.1367332 -0.09292382 0.225 0.133747 -0.09717285 0.225 0.1306287 -0.101326 0.225 0.1273816 -0.1053792 0.225 0.1240087 -0.1093283 0.225 0.1205134 -0.1131696 0.225 0.1168992 -0.1168992 0.225 0.1131696 -0.1205134 0.225 0.1093283 -0.1240087 0.225 0.1053792 -0.1273816 0.225 0.101326 -0.1306287 0.225 0.09717285 -0.133747 0.225 0.09292382 -0.1367332 0.225 0.08858305 -0.1395846 0.225 0.0841549 -0.1422982 0.225 0.07964366 -0.1448714 0.225 0.07505387 -0.1473014 0.225 0.07038998 -0.1495864 0.225 0.0656566 -0.1517236 0.225 0.06085848 -0.153711 0.225 0.05600029 -0.1555468 0.225 0.05108678 -0.157229 0.225 0.0461229 -0.1587561 0.225 0.04111349 -0.1601266 0.225 0.03606349 -0.1613389 0.225 0.0309779 -0.1623921 0.225 0.02586179 -0.163285 0.225 0.02072012 -0.1640168 0.225 0.015558 -0.1645867 0.225 0.0103805 -0.1649942 0.225 0.005192816 -0.1652387 0.225 0 -0.1653203 0.225 -0.005192816 -0.1652387 0.225 -0.0103805 -0.1649942 0.225 -0.015558 -0.1645867 0.225 -0.02072012 -0.1640168 0.225 -0.02586179 -0.163285 0.225 -0.0309779 -0.1623921 0.225 -0.03606349 -0.1613389 0.225 -0.04111349 -0.1601266 0.225 -0.0461229 -0.1587561 0.225 -0.05108678 -0.157229 0.225 -0.05600029 -0.1555468 0.225 -0.06085848 -0.153711 0.225 -0.0656566 -0.1517236 0.225 -0.07038998 -0.1495864 0.225 -0.07505387 -0.1473014 0.225 -0.07964366 -0.1448714 0.225 -0.0841549 -0.1422982 0.225 -0.08858305 -0.1395846 0.225 -0.09292382 -0.1367332 0.225 -0.09717285 -0.133747 0.225 -0.101326 -0.1306287 0.225 -0.1053792 -0.1273816 0.225 -0.1093283 -0.1240087 0.225 -0.1131696 -0.1205134 0.225 -0.1168992 -0.1168992 0.225 -0.1205134 -0.1131696 0.225 -0.1240087 -0.1093283 0.225 -0.1273816 -0.1053792 0.225 -0.1306287 -0.101326 0.225 -0.133747 -0.09717285 0.225 -0.1367332 -0.09292382 0.225 -0.1395846 -0.08858305 0.225 -0.1422982 -0.0841549 0.225 -0.1448714 -0.07964366 0.225 -0.1473014 -0.07505387 0.225 -0.1495864 -0.07038998 0.225 -0.1517236 -0.0656566 0.225 -0.153711 -0.06085848 0.225 -0.1555468 -0.05600029 0.225 -0.157229 -0.05108678 0.225 -0.1587561 -0.0461229 0.225 -0.1601266 -0.04111349 0.225 -0.1609623 -0.03763234 0.202 -0.1613389 -0.03606349 0.202 -0.1613389 -0.03606349 0.225 -0.1613389 -0.03606349 0.1635 -0.1623921 -0.0309779 0.1635 -0.163285 -0.02586179 0.1635 -0.1640168 -0.02072012 0.1635 -0.1645867 -0.015558 0.1635 -0.1649942 0.0103805 0.1635 -0.1645867 0.015558 0.1635 -0.1640168 0.02072012 0.1635 -0.163285 0.02586179 0.1635 -0.1623921 0.0309779 0.1635 -0.1613389 0.03606349 0.1635 -0.1649942 -0.0103805 0.1635 -0.1652387 -0.005192816 0.1635 -0.1653203 0 0.1635 -0.1652387 0.005192816 0.1635 0.02840322 0.04114913 0.225 -0.03742551 -0.03315609 0.225 -0.04427278 -0.02323615 0.225 0.01773023 0.04675078 0.225 -0.04854708 -0.01196575 0.225 0.006026804 0.04963541 0.225 -0.1623921 -0.0309779 0.225 -0.163285 -0.02586179 0.225 -0.04999995 0 0.225 -0.1640168 -0.02072012 0.225 -0.1645867 -0.015558 0.225 -0.1649942 -0.0103805 0.225 -0.1652387 -0.005192816 0.225 -0.006026804 0.04963541 0.225 -0.1653203 0 0.225 -0.1652387 0.005192816 0.225 -0.1649942 0.0103805 0.225 -0.1645867 0.015558 0.225 -0.04854708 0.01196575 0.225 -0.1640168 0.02072012 0.225 -0.163285 0.02586179 0.225 -0.1623921 0.0309779 0.225 -0.01773023 0.04675078 0.225 0.03742551 -0.03315609 0.225 -0.04427278 0.02323615 0.225 -0.02840322 0.04114913 0.225 0.02840322 -0.04114913 0.225 -0.03742551 0.03315609 0.225 0.04427278 -0.02323615 0.225 0.01773023 -0.04675078 0.225 0.04854708 -0.01196575 0.225 0.006026804 -0.04963541 0.225 0.04999995 0 0.225 -0.006026804 -0.04963541 0.225 0.04854708 0.01196575 0.225 -0.01773023 -0.04675078 0.225 0.04427278 0.02323615 0.225 -0.02840322 -0.04114913 0.225 0.03742551 0.03315609 0.225 -0.1623921 0.0309779 0.202 -0.1623921 -0.0309779 0.202 -0.163285 -0.02586179 0.202 -0.1640168 -0.02072012 0.202 -0.1645867 -0.015558 0.202 -0.1649942 -0.0103805 0.202 -0.1652387 -0.005192816 0.202 -0.1653203 0 0.202 -0.1652387 0.005192816 0.202 -0.1649942 0.0103805 0.202 -0.1645867 0.015558 0.202 -0.1640168 0.02072012 0.202 -0.163285 0.02586179 0.202 0.01773023 -0.04675078 0.215 0.006026804 -0.04963541 0.215 -0.006026804 -0.04963541 0.215 -0.04999995 0 0.215 -0.04854708 0.01196575 0.215 -0.01773023 -0.04675078 0.215 -0.04427278 0.02323615 0.215 -0.02840322 -0.04114913 0.215 -0.03742551 -0.03315609 0.215 -0.03742551 0.03315609 0.215 -0.04427278 -0.02323615 0.215 -0.02840322 0.04114913 0.215 -0.04854708 -0.01196575 0.215 -0.01773023 0.04675078 0.215 -0.006026804 0.04963541 0.215 0.006026804 0.04963541 0.215 0.01773023 0.04675078 0.215 0.02840322 0.04114913 0.215 0.03742551 0.03315609 0.215 0.04427278 0.02323615 0.215 0.04854708 0.01196575 0.215 0.04999995 0 0.215 0.04854708 -0.01196575 0.215 0.04427278 -0.02323615 0.215 0.03742551 -0.03315609 0.215 0.02840322 -0.04114913 0.215 + + + + + + + + + + -0.911405 0.4115106 0 -0.9114034 0.4115142 0 -0.9114054 0.4115097 0 -0.9238788 0.3826853 0 0 0 -1 0 0 -1 -2.00956e-7 0 -1 2.09639e-7 0 -1 2.09647e-6 0 -1 -2.5001e-6 0 -1 3.03461e-6 0 -1 0 0 -1 -4.79019e-6 0 -1 6.30947e-6 0 -1 9.53216e-6 0 -1 -1.19048e-5 0 -1 -3.07443e-6 0 -1 -6.82282e-6 0 -1 -1.30389e-6 0 -1 -1.51495e-6 0 -1 1.15384e-6 0 -1 1.04913e-5 0 -1 -8.01937e-6 0 -1 -1.45068e-5 0 -1 8.48395e-7 0 -1 -7.91946e-7 0 -1 7.41312e-7 0 -1 -5.52154e-7 0 -1 5.23845e-7 0 -1 -4.97889e-7 0 -1 1.3748e-7 0 -1 -4.13106e-7 0 -1 -7.25342e-6 0 -1 3.64717e-7 0 -1 -9.75914e-6 0 -1 2.01045e-5 0 -1 2.29822e-5 0 -1 -1.39966e-5 0 -1 2.93901e-7 0 -1 6.71105e-6 0 -1 -3.93091e-6 0 -1 -1.37931e-7 0 -1 1.33828e-7 0 -1 -2.73645e-6 0 -1 -1.29966e-7 0 -1 5.43244e-6 0 -1 -4.20368e-6 0 -1 1.22908e-7 0 -1 2.51276e-6 0 -1 -1.19679e-7 0 -1 -3.41729e-6 0 -1 4.26467e-6 0 -1 -1.20158e-6 0 -1 -2.05897e-7 0 -1 0 0 -1 8.9236e-7 0 -1 0 0 -1 -9.37426e-7 0 -1 -2.75978e-7 0 -1 6.14048e-7 0 -1 -9.35525e-7 0 -1 3.96984e-7 0 -1 4.04955e-7 0 -1 -4.10052e-7 0 -1 0 0 -1 4.14184e-7 0 -1 -5.73391e-7 0 -1 0 0 -1 0 0 -1 -3.70609e-7 0 -1 6.09299e-7 0 -1 -2.23974e-7 0 -1 -1.63827e-7 0 -1 5.15629e-7 0 -1 -7.53276e-7 0 -1 1.91811e-7 0 -1 4.24869e-7 0 -1 0 0 -1 -5.62681e-7 0 -1 5.35283e-7 0 -1 0 0 -1 3.04159e-7 0 -1 -3.30904e-7 0 -1 0 0 -1 -1.35104e-7 0 -1 0 0 -1 4.79521e-7 0 -1 -2.96402e-7 0 -1 0 0 -1 0 0 -1 -2.84695e-7 0 -1 1.55812e-7 0 -1 0 0 -1 0 0 -1 1.73669e-7 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 1.36027e-7 0 -1 -1.67097e-7 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 -1.74447e-7 0 -1 0 0 -1 0 0 -1 -0.8980141 0.4399666 0 -0.898005 0.4399854 0 -0.9238781 0.3826872 0 -0.92388 0.3826825 0 -1.73279e-6 0 -1 3.46553e-6 0 -1 -6.79269e-6 0 -1 -6.79265e-6 0 -1 6.93112e-6 0 -1 -6.93112e-6 0 -1 5.09455e-6 0 -1 6.79254e-6 0 -1 -5.19826e-6 0 -1 3.4655e-6 0 -1 6.79249e-6 0 -1 6.93099e-6 0 -1 1.69815e-6 0 -1 -6.93092e-6 0 -1 -6.79267e-6 0 -1 8.4909e-6 0 -1 -6.93096e-6 0 -1 -3.46547e-6 0 -1 3.46548e-6 0 -1 -6.79258e-6 0 -1 6.93097e-6 0 -1 6.79265e-6 0 -1 -3.46548e-6 0 -1 -6.79249e-6 0 -1 2.59915e-6 0 -1 -3.46558e-6 0 -1 -6.79272e-6 0 -1 3.46556e-6 0 -1 6.9308e-6 0 -1 3.39629e-6 0 -1 -6.93116e-6 0 -1 1.38616e-5 0 -1 6.93096e-6 0 -1 -6.79251e-6 0 -1 6.93106e-6 0 -1 -6.93102e-6 0 -1 6.79253e-6 0 -1 3.46551e-6 0 -1 -3.39628e-6 0 -1 6.93102e-6 0 -1 1.38616e-5 0 -1 -3.3963e-6 0 -1 -3.46546e-6 0 -1 1.35849e-5 0 -1 -6.9308e-6 0 -1 6.93092e-6 0 -1 6.7926e-6 0 -1 -6.79244e-6 0 -1 -6.93106e-6 0 -1 -3.46545e-6 0 -1 -1.38619e-5 0 -1 6.79272e-6 0 -1 -5.09438e-6 0 -1 6.93088e-6 0 -1 1.3585e-5 0 -1 6.93116e-6 0 -1 1.35855e-5 0 -1 6.79262e-6 0 -1 1.35854e-5 0 -1 3.39631e-6 0 -1 -4.2454e-6 0 -1 -3.39635e-6 0 -1 3.39628e-6 0 -1 -6.93094e-6 0 -1 -6.93097e-6 0 -1 -6.79271e-6 0 -1 3.39632e-6 0 -1 3.39634e-6 0 -1 3.39642e-6 0 -1 -3.39628e-6 0 -1 -3.46556e-6 0 -1 6.79264e-6 0 -1 -3.46551e-6 0 -1 6.79273e-6 0 -1 1.69817e-6 0 -1 -3.4655e-6 0 -1 -5.0945e-6 0 -1 1.35854e-5 0 -1 6.06471e-6 0 -1 -1.35855e-5 0 -1 -1.73276e-6 0 -1 -1.69817e-6 0 -1 8.49095e-7 0 -1 -1.73274e-6 0 -1 -8.49074e-7 0 -1 5.09438e-6 0 -1 1.69818e-6 0 -1 6.06455e-6 0 -1 -5.09452e-6 0 -1 1.27362e-6 0 -1 -6.79267e-6 0 -1 1.38619e-5 0 -1 -6.93094e-6 0 -1 -2.54724e-6 0 -1 6.931e-6 0 -1 0 0 -1 -1.38619e-5 0 -1 6.93094e-6 0 -1 5.09452e-6 0 -1 -1.27361e-6 0 -1 -6.79258e-6 0 -1 8.66366e-7 0 -1 -6.93095e-6 0 -1 1.69815e-6 0 -1 7.64166e-6 0 -1 -2.46342e-6 0 -1 -3.39637e-6 0 -1 -7.64187e-6 0 -1 1.73277e-6 0 -1 8.66385e-7 0 -1 4.33185e-6 0 -1 -6.93094e-6 0 -1 -1.69815e-6 0 -1 6.79256e-6 0 -1 -8.66365e-7 0 -1 -1.73276e-6 0 -1 3.46546e-6 0 -1 5.09434e-6 0 -1 -4.11529e-6 0 -1 6.79269e-6 0 -1 6.06455e-6 0 -1 1.73278e-6 0 -1 -6.79274e-6 0 -1 -6.79286e-6 0 -1 1.73278e-6 0 -1 -1.69815e-6 0 -1 -3.39632e-6 0 -1 -1.73277e-6 0 -1 -1.73277e-6 0 -1 3.3963e-6 0 -1 3.46551e-6 0 -1 -0.8980334 0.4399273 0 -0.8980199 0.4399548 0 -0.8980269 0.4399406 -1.19482e-6 -0.8980293 0.4399356 0 -0.9354459 0.3534702 0 -0.9354441 0.3534747 0 -0.8837656 0.4679299 0 -0.8837622 0.4679363 0 -0.868631 0.4954596 0 -0.8686292 0.4954628 0 -0.8526406 0.5224981 0 -0.8526405 0.522498 0 -0.8358092 0.5490201 0 -0.8358073 0.5490231 0 -0.8181493 0.5750061 0 -0.8181473 0.5750089 0 -0.7996867 0.6004176 0 -0.7996847 0.6004203 0 -0.7804249 0.6252497 0 -0.7604099 0.6494436 0 -0.7396333 0.6730102 0 -0.7396332 0.6730102 0 -0.7181217 0.6959176 0 -0.7181196 0.6959198 0 -0.695918 0.7181213 0 -0.6730116 0.739632 0 -0.6730095 0.7396339 0 -0.6494449 0.7604086 0 -0.6494429 0.7604106 0 -0.6252501 0.7804245 0 -0.625248 0.7804261 0 -0.6004188 0.7996857 0 -0.6004189 0.7996857 0 -0.5750097 0.8181467 0 -0.5750077 0.818148 0 -0.5490217 0.8358081 0 -0.5490207 0.8358088 0 -0.5224978 0.8526406 0 -0.4954611 0.8686302 0 -0.4954612 0.8686302 0 -0.467934 0.8837634 0 -0.4679331 0.8837639 0 -0.4399399 0.8980273 0 -0.4399392 0.8980277 0 -0.4115098 0.9114054 0 -0.4115107 0.911405 0 -0.3826864 0.9238783 0 -0.3826858 0.9238787 0 -0.3534728 0.9354448 0 -0.3534721 0.9354451 0 -0.3239209 0.9460843 0 -0.3239216 0.946084 0 -0.294039 0.9557935 0 -0.2940396 0.9557933 0 -0.2638637 0.96456 0 -0.2638638 0.96456 0 -0.2334455 0.97237 0 -0.2334455 0.97237 0 -0.2027977 0.9792207 0 -0.2027981 0.9792206 0 -0.171932 0.9851089 0 -0.1719322 0.9851088 0 -0.1408906 0.9900252 0 -0.1408905 0.9900252 0 -0.1097285 0.9939616 0 -0.1097285 0.9939616 0 -0.07846975 0.9969165 0 -0.07846975 0.9969165 0 -0.04709422 0.9988905 0 -0.04709422 0.9988905 0 -0.01571851 0.9998765 0 -0.01571851 0.9998765 0 0.01571851 0.9998765 0 0.01571851 0.9998765 0 0.04709422 0.9988905 0 0.04709422 0.9988905 0 0.07846975 0.9969165 0 0.07846975 0.9969165 0 0.1097285 0.9939616 0 0.1097285 0.9939616 0 0.1408905 0.9900252 0 0.1408906 0.9900252 0 0.1719322 0.9851088 0 0.171932 0.9851089 0 0.2027981 0.9792206 0 0.2027977 0.9792207 0 0.2334455 0.97237 0 0.2334455 0.97237 0 0.2638637 0.96456 0 0.2638638 0.96456 0 0.2940396 0.9557933 0 0.294039 0.9557935 0 0.3239215 0.946084 0 0.3239209 0.9460843 0 0.3534721 0.9354451 0 0.3534728 0.9354448 0 0.3826858 0.9238787 0 0.3826865 0.9238783 0 0.4115107 0.911405 0 0.4115098 0.9114054 0 0.4399392 0.8980277 0 0.4399399 0.8980273 0 0.4679331 0.8837639 0 0.467934 0.8837634 0 0.4954611 0.8686302 0 0.4954612 0.8686302 0 0.5224978 0.8526406 0 0.5490208 0.8358088 0 0.5490217 0.8358081 0 0.5750077 0.818148 0 0.5750097 0.8181467 0 0.6004189 0.7996857 0 0.6004188 0.7996857 0 0.6252481 0.7804261 0 0.6252501 0.7804245 0 0.6494429 0.7604106 0 0.6494449 0.7604086 0 0.6730095 0.7396339 0 0.6730116 0.739632 0 0.695918 0.7181213 0 0.7181196 0.6959198 0 0.7181217 0.6959176 0 0.7396333 0.6730102 0 0.7396332 0.6730102 0 0.7604099 0.6494436 0 0.7804249 0.6252497 0 0.7996847 0.6004203 0 0.7996867 0.6004176 0 0.8181473 0.5750089 0 0.8181493 0.5750061 0 0.8358073 0.549023 0 0.8358092 0.5490201 0 0.8526405 0.522498 0 0.8526406 0.5224981 0 0.8686292 0.4954628 0 0.868631 0.4954597 0 0.8837622 0.4679363 0 0.8837656 0.4679299 0 0.8980274 0.4399394 0 0.8980275 0.4399394 0 0.9114052 0.4115104 0 0.9114051 0.4115105 0 0.9238783 0.3826865 0 0.9354452 0.353472 0 0.9354452 0.353472 0 0.9460833 0.3239233 0 0.9460846 0.3239196 0 0.9557929 0.294041 0 0.955794 0.2940372 0 0.9645596 0.2638653 0 0.9645607 0.2638614 0 0.9723696 0.233447 0 0.9723705 0.2334431 0 0.9792207 0.2027979 0 0.9792207 0.202798 0 0.9851088 0.1719325 0 0.9851088 0.1719325 0 0.9900252 0.1408914 0 0.9900251 0.1408914 0 0.9939617 0.1097285 0 0.9969162 0.0784735 0 0.9969169 0.07846522 0 0.9988905 0.04709339 0 0.9998765 0.01572144 0 0.9998766 0.01571726 0 0.9998765 -0.01571726 0 0.9998764 -0.01572144 0 0.9988905 -0.04709339 0 0.9969169 -0.07846522 0 0.9969162 -0.0784735 0 0.9939617 -0.1097285 0 0.9900252 -0.1408914 0 0.9900251 -0.1408914 0 0.9851088 -0.1719325 0 0.9851088 -0.1719325 0 0.9792207 -0.2027979 0 0.9792207 -0.202798 0 0.9723705 -0.2334431 0 0.9723696 -0.233447 0 0.9645607 -0.2638614 0 0.9645596 -0.2638653 0 0.955794 -0.2940372 0 0.9557929 -0.294041 0 0.9460847 -0.3239196 0 0.9460834 -0.3239234 0 0.9354452 -0.353472 0 0.9354452 -0.353472 0 0.9238783 -0.3826865 0 0.9114052 -0.4115104 0 0.9114051 -0.4115105 0 0.8980275 -0.4399394 0 0.8980274 -0.4399394 0 0.8837656 -0.4679298 0 0.8837621 -0.4679364 0 0.868631 -0.4954597 0 0.8686292 -0.4954628 0 0.8526405 -0.522498 0 0.8526406 -0.5224981 0 0.8358092 -0.5490201 0 0.8358073 -0.5490231 0 0.8181493 -0.5750061 0 0.8181473 -0.5750089 0 0.7996867 -0.6004176 0 0.7996847 -0.6004203 0 0.7804249 -0.6252497 0 0.7604099 -0.6494436 0 0.7396332 -0.6730102 0 0.7396333 -0.6730102 0 0.7181217 -0.6959176 0 0.7181196 -0.6959198 0 0.695918 -0.7181213 0 0.6730116 -0.739632 0 0.6730095 -0.7396339 0 0.6494449 -0.7604086 0 0.6494429 -0.7604106 0 0.6252501 -0.7804245 0 0.6252481 -0.7804261 0 0.6004189 -0.7996857 0 0.6004188 -0.7996857 0 0.5750097 -0.8181467 0 0.5750077 -0.818148 0 0.5490217 -0.8358081 0 0.5490207 -0.8358088 0 0.5224978 -0.8526406 0 0.4954611 -0.8686302 0 0.4954612 -0.8686302 0 0.467934 -0.8837634 0 0.4679331 -0.8837639 0 0.4399399 -0.8980273 0 0.4399392 -0.8980277 0 0.4115098 -0.9114054 0 0.4115107 -0.911405 0 0.3826864 -0.9238783 0 0.3826858 -0.9238787 0 0.3534728 -0.9354448 0 0.3534721 -0.9354451 0 0.3239209 -0.9460843 0 0.3239215 -0.946084 0 0.294039 -0.9557935 0 0.2940396 -0.9557933 0 0.2638638 -0.96456 0 0.2638637 -0.96456 0 0.2334455 -0.97237 0 0.2334455 -0.97237 0 0.2027977 -0.9792207 0 0.2027981 -0.9792206 0 0.171932 -0.9851089 0 0.1719322 -0.9851088 0 0.1408906 -0.9900252 0 0.1408905 -0.9900252 0 0.1097285 -0.9939616 0 0.1097285 -0.9939616 0 0.07846975 -0.9969165 0 0.07846975 -0.9969165 0 0.04709422 -0.9988905 0 0.04709422 -0.9988905 0 0.01571851 -0.9998765 0 0.01571851 -0.9998765 0 -0.01571851 -0.9998765 0 -0.01571851 -0.9998765 0 -0.04709422 -0.9988905 0 -0.04709422 -0.9988905 0 -0.07846975 -0.9969165 0 -0.07846975 -0.9969165 0 -0.1097285 -0.9939616 0 -0.1097285 -0.9939616 0 -0.1408905 -0.9900252 0 -0.1408905 -0.9900252 0 -0.1719322 -0.9851088 0 -0.171932 -0.9851089 0 -0.2027981 -0.9792206 0 -0.2027977 -0.9792207 0 -0.2334455 -0.97237 0 -0.2334455 -0.97237 0 -0.2638637 -0.96456 0 -0.2638638 -0.96456 0 -0.2940396 -0.9557933 0 -0.294039 -0.9557935 0 -0.3239216 -0.946084 0 -0.3239209 -0.9460843 0 -0.3534721 -0.9354451 0 -0.3534728 -0.9354448 0 -0.3826858 -0.9238787 0 -0.3826865 -0.9238783 0 -0.4115106 -0.911405 0 -0.4115099 -0.9114054 0 -0.4399392 -0.8980277 0 -0.4399399 -0.8980273 0 -0.4679331 -0.8837639 0 -0.467934 -0.8837634 0 -0.4954612 -0.8686302 0 -0.4954611 -0.8686302 0 -0.5224978 -0.8526406 0 -0.5490208 -0.8358088 0 -0.5490217 -0.8358081 0 -0.5750077 -0.818148 0 -0.5750097 -0.8181467 0 -0.6004189 -0.7996857 0 -0.6004188 -0.7996857 0 -0.625248 -0.7804261 0 -0.6252501 -0.7804245 0 -0.6494429 -0.7604106 0 -0.6494449 -0.7604086 0 -0.6730095 -0.7396339 0 -0.6730116 -0.739632 0 -0.695918 -0.7181213 0 -0.7181196 -0.6959198 0 -0.7181217 -0.6959176 0 -0.7396333 -0.6730102 0 -0.7396332 -0.6730102 0 -0.7604099 -0.6494436 0 -0.7804249 -0.6252497 0 -0.7996847 -0.6004203 0 -0.7996867 -0.6004176 0 -0.8181473 -0.5750089 0 -0.8181493 -0.5750061 0 -0.8358028 -0.5490298 0 -0.8358069 -0.5490236 0 -0.8358074 -0.5490228 -3.41378e-7 -0.8358192 -0.5490048 0 -0.8358087 -0.5490208 0 -0.8358056 -0.5490257 0 -0.8526406 -0.522498 0 -0.8526406 -0.522498 0 -0.8686323 -0.4954573 0 -0.8686279 -0.4954651 0 -0.8837627 -0.4679356 0 -0.8837648 -0.4679316 0 -0.8980271 -0.4399402 0 -0.911405 -0.4115106 0 -0.9238788 -0.3826853 0 -0.9354459 -0.3534702 0 -0.9354441 -0.3534747 0 -0.9460831 -0.323924 0 -0.9460848 -0.3239194 0 -0.9557937 -0.2940382 0 -0.9645593 -0.2638664 0 -0.9645606 -0.2638615 0 -0.972368 -0.2334536 0 -0.9723696 -0.2334469 0 -1 0 0 -0.972368 0.2334536 0 -0.9723696 0.2334469 0 -0.9645593 0.2638664 0 -0.9645606 0.2638615 0 -0.9557937 0.2940382 0 -0.9460831 0.323924 0 -0.9460848 0.3239194 0 -0.9354439 0.3534751 0 -0.9354457 0.3534703 0 0.2926305 -0.9562256 0 0.2926331 -0.9562248 0 -0.9723704 -0.2334433 0 -0.9723687 -0.2334508 0 -0.9645594 -0.2638658 0 -0.9645595 -0.2638655 0 -0.9557921 -0.2940433 0 -0.9557952 -0.2940335 0 -0.9460843 -0.3239207 0 -0.9460843 -0.3239204 0 -0.9354457 -0.3534703 0 -0.9354439 -0.3534751 0 -0.92388 -0.3826825 0 -0.9238781 -0.3826872 0 -0.9114054 -0.4115097 0 -0.9114034 -0.4115142 0 -0.898029 -0.4399362 0 -0.8980269 -0.4399406 0 -0.8837624 -0.467936 0 -0.8837649 -0.4679312 0 -0.8686301 -0.4954612 0 -0.8686299 -0.4954614 0 -0.8526405 -0.5224981 0 -0.8526401 -0.5224987 0 -0.9460843 0.3239207 0 -0.9460843 0.3239204 0 -0.9557952 0.2940332 0 -0.9557921 0.2940434 0 -0.9645595 0.2638655 0 -0.9645594 0.2638658 0 -0.9723687 0.2334508 0 -0.9723704 0.2334433 0 0.2926305 0.9562256 0 0.2926331 0.9562248 0 -0.9723742 0.2334275 0 -0.9723793 0.2334064 0 -0.9723742 0.233428 7.91861e-7 -0.9723723 0.2334358 0 -0.9645547 0.2638834 0 -0.9645531 0.2638888 0 -0.9557924 0.2940422 0 -0.9460888 0.3239073 0 -0.9460887 0.3239076 0 -0.9354417 0.3534813 0 -0.923883 0.3826751 0 -0.9238827 0.3826759 0 -0.9114012 0.411519 0 -0.9114038 0.4115134 0 -0.8980237 0.4399471 0 -0.8980215 0.4399517 0 -0.8837735 0.4679151 0 -0.8837708 0.4679201 0 -0.8686298 0.4954618 0 -0.8686268 0.495467 0 -0.8526407 0.5224978 0 -0.8526352 0.5225067 0 -0.83581 0.549019 0 -0.8358112 0.5490171 0 -0.8181465 0.57501 0 -0.818151 0.5750035 0 -0.7996824 0.6004234 0 -0.7996777 0.6004295 0 -0.78044 0.6252307 0 -0.7804414 0.6252292 0 -0.7604027 0.649452 0 -0.760401 0.6494539 0 -0.7396339 0.6730095 0 -0.7396323 0.6730112 0 -0.7181277 0.6959114 0 -0.7181296 0.6959093 0 -0.6959098 0.7181293 0 -0.6959102 0.7181289 0 -0.673012 0.7396317 0 -0.6730099 0.7396335 0 -0.6494538 0.7604011 0 -0.6494522 0.7604026 0 -0.6252277 0.7804425 0 -0.6252313 0.7804396 0 -0.6004257 0.7996807 0 -0.6004272 0.7996794 0 -0.5750059 0.8181493 0 -0.575008 0.8181478 0 -0.5490188 0.83581 0 -0.5490193 0.8358097 0 -0.5225014 0.8526384 0 -0.5225023 0.852638 0 -0.4954653 0.8686278 0 -0.4954633 0.8686289 0 -0.4679174 0.8837723 0 -0.467916 0.8837729 0 -0.4399501 0.8980223 0 -0.439953 0.8980209 0 -0.4115159 0.9114025 0 -0.4115157 0.9114027 0 -0.3826755 0.9238829 0 -0.3826763 0.9238826 0 -0.3534795 0.9354423 0 -0.3239083 0.9460886 0 -0.3239086 0.9460884 0 -0.2940418 0.9557926 0 -0.2638859 0.9645539 0 -0.2638852 0.9645542 0 -0.2334281 0.9723742 0 -0.2334283 0.9723741 0 -0.2027922 0.9792219 0 -0.1719288 0.9851094 0 -0.1719287 0.9851094 0 -0.1409064 0.990023 0 -0.1409065 0.990023 0 -0.1097327 0.9939612 0 -0.1097328 0.9939612 0 -0.07846409 0.996917 0 -0.04709804 0.9988903 0 -0.01571178 0.9998766 0 -0.01571172 0.9998766 0 0.01571178 0.9998766 0 0.01571172 0.9998766 0 0.04709804 0.9988903 0 0.07846409 0.996917 0 0.1097328 0.9939612 0 0.1097327 0.9939612 0 0.1409064 0.990023 0 0.1409065 0.990023 0 0.1719288 0.9851094 0 0.1719287 0.9851094 0 0.2027922 0.9792219 0 0.2334281 0.9723742 0 0.2334283 0.9723741 0 0.2638852 0.9645542 0 0.2638859 0.9645539 0 0.2940418 0.9557926 0 0.3239083 0.9460886 0 0.3239086 0.9460884 0 0.3534795 0.9354423 0 0.3826766 0.9238824 0 0.3826751 0.923883 0 0.4115154 0.9114028 0 0.4115163 0.9114025 0 0.4399501 0.8980223 0 0.439953 0.8980209 0 0.4679174 0.8837723 0 0.467916 0.8837729 0 0.4954653 0.8686278 0 0.4954633 0.8686289 0 0.5225014 0.8526384 0 0.5225023 0.852638 0 0.5490188 0.83581 0 0.5490193 0.8358097 0 0.5750074 0.8181482 0 0.5750065 0.8181489 0 0.6004272 0.7996794 0 0.6004257 0.7996807 0 0.6252308 0.7804399 0 0.6252282 0.7804421 0 0.6494538 0.7604011 0 0.6494522 0.7604026 0 0.673012 0.7396317 0 0.6730099 0.7396335 0 0.6959098 0.7181293 0 0.6959102 0.7181289 0 0.7181277 0.6959114 0 0.7181296 0.6959093 0 0.7396323 0.6730112 0 0.7396339 0.6730095 0 0.760401 0.6494539 0 0.7604027 0.649452 0 0.7804416 0.6252288 0 0.7804397 0.6252311 0 0.7996777 0.6004295 0 0.7996824 0.6004234 0 0.818151 0.5750035 0 0.8181465 0.57501 0 0.83581 0.549019 0 0.8358112 0.5490171 0 0.852635 0.5225071 0 0.8526409 0.5224975 0 0.8686298 0.4954618 0 0.8686268 0.495467 0 0.8837708 0.4679201 0 0.8837735 0.4679151 0 0.8980212 0.4399523 0 0.898024 0.4399465 0 0.9114012 0.411519 0 0.9114038 0.4115134 0 0.923883 0.3826751 0 0.9238827 0.3826759 0 0.9354417 0.3534813 0 0.9460888 0.3239073 0 0.9460887 0.3239076 0 0.9557924 0.2940422 0 0.9645547 0.2638834 0 0.9645531 0.2638888 0 0.9723747 0.2334253 0 0.9723734 0.2334309 0 0.9792209 0.2027968 0 0.9792233 0.2027848 0 0.9851095 0.1719284 0 0.9900223 0.1409111 0 0.9900233 0.1409046 0 0.993961 0.1097342 0 0.9939617 0.109728 0 0.9969173 0.07846117 0 0.9969167 0.07846754 0 0.9988902 0.04709857 0 0.9998765 0.01571655 0 0.9998766 0.01571017 0 0.9998766 -0.01571017 0 0.9998765 -0.01571655 0 0.9988902 -0.04709857 0 0.9969167 -0.07846754 0 0.9969173 -0.07846117 0 0.993961 -0.1097342 0 0.9939617 -0.109728 0 0.9900231 -0.1409049 0 0.9900223 -0.1409109 0 0.9851095 -0.1719284 0 0.9792234 -0.2027845 0 0.9792209 -0.2027971 0 0.9723734 -0.2334313 0 0.9723749 -0.2334249 0 0.9645547 -0.2638834 0 0.9645531 -0.2638888 0 0.9557924 -0.2940422 0 0.9460888 -0.3239073 0 0.9460887 -0.3239076 0 0.9354417 -0.3534813 0 0.923883 -0.3826751 0 0.9238827 -0.3826759 0 0.9114037 -0.4115137 0 0.9114014 -0.4115187 0 0.8980212 -0.4399523 0 0.898024 -0.4399465 0 0.8837735 -0.4679151 0 0.8837708 -0.4679201 0 0.868627 -0.4954667 0 0.8686295 -0.4954622 0 0.852635 -0.5225071 0 0.8526409 -0.5224975 0 0.8358114 -0.5490168 0 0.8358097 -0.5490193 0 0.8181465 -0.57501 0 0.818151 -0.5750035 0 0.7996777 -0.6004295 0 0.7996824 -0.6004234 0 0.78044 -0.6252307 0 0.7804414 -0.6252292 0 0.7604027 -0.649452 0 0.760401 -0.6494539 0 0.7396339 -0.6730095 0 0.7396323 -0.6730112 0 0.7181277 -0.6959114 0 0.7181296 -0.6959093 0 0.6959098 -0.7181293 0 0.6959102 -0.7181289 0 0.6730104 -0.7396331 0 0.6730116 -0.7396321 0 0.6494538 -0.7604011 0 0.6494522 -0.7604026 0 0.6252277 -0.7804425 0 0.6252313 -0.7804396 0 0.6004257 -0.7996807 0 0.6004272 -0.7996794 0 0.5750059 -0.8181493 0 0.575008 -0.8181478 0 0.5490188 -0.83581 0 0.5490193 -0.8358097 0 0.5225014 -0.8526384 0 0.5225023 -0.852638 0 0.495464 -0.8686286 0 0.4954647 -0.8686281 0 0.4679174 -0.8837723 0 0.467916 -0.8837729 0 0.4399501 -0.8980223 0 0.439953 -0.8980209 0 0.4115159 -0.9114025 0 0.4115157 -0.9114027 0 0.3826766 -0.9238824 0 0.3826751 -0.923883 0 0.3534795 -0.9354423 0 0.3239083 -0.9460886 0 0.3239086 -0.9460884 0 0.2940418 -0.9557926 0 0.2638852 -0.9645542 0 0.2638859 -0.9645539 0 0.2334281 -0.9723742 0 0.2334283 -0.9723741 0 0.2027922 -0.9792219 0 0.1719288 -0.9851094 0 0.1719287 -0.9851094 0 0.1409065 -0.990023 0 0.1409064 -0.990023 0 0.1097328 -0.9939612 0 0.1097327 -0.9939612 0 0.07846409 -0.996917 0 0.04709804 -0.9988903 0 0.01571178 -0.9998766 0 0.01571172 -0.9998766 0 -0.01571178 -0.9998766 0 -0.01571172 -0.9998766 0 -0.04709804 -0.9988903 0 -0.07846409 -0.996917 0 -0.1097328 -0.9939612 0 -0.1097327 -0.9939612 0 -0.1409065 -0.990023 0 -0.1409064 -0.990023 0 -0.1719288 -0.9851094 0 -0.1719287 -0.9851094 0 -0.2027922 -0.9792219 0 -0.2334281 -0.9723742 0 -0.2334283 -0.9723741 0 -0.2638852 -0.9645542 0 -0.2638859 -0.9645539 0 -0.2940418 -0.9557926 0 -0.3239083 -0.9460886 0 -0.3239086 -0.9460884 0 -0.3534795 -0.9354423 0 -0.3826766 -0.9238824 0 -0.3826751 -0.923883 0 -0.4115154 -0.9114028 0 -0.4115163 -0.9114025 0 -0.4399526 -0.898021 0 -0.4399504 -0.8980221 0 -0.4679174 -0.8837723 0 -0.467916 -0.8837729 0 -0.4954653 -0.8686278 0 -0.4954633 -0.8686289 0 -0.5225028 -0.8526376 0 -0.5225008 -0.8526389 0 -0.5490188 -0.83581 0 -0.5490193 -0.8358097 0 -0.5750074 -0.8181482 0 -0.5750065 -0.8181489 0 -0.6004257 -0.7996807 0 -0.6004272 -0.7996794 0 -0.6252308 -0.7804399 0 -0.6252282 -0.7804421 0 -0.6494522 -0.7604026 0 -0.6494538 -0.7604011 0 -0.673012 -0.7396317 0 -0.6730099 -0.7396335 0 -0.6959098 -0.7181293 0 -0.6959102 -0.7181289 0 -0.7181293 -0.6959098 0 -0.7181281 -0.695911 0 -0.7396323 -0.6730112 0 -0.7396339 -0.6730095 0 -0.760401 -0.6494539 0 -0.7604027 -0.649452 0 -0.78044 -0.6252307 0 -0.7804414 -0.6252292 0 -0.7996777 -0.6004295 0 -0.7996824 -0.6004234 0 -0.818151 -0.5750035 0 -0.8181465 -0.57501 0 -0.83581 -0.549019 0 -0.8358112 -0.5490171 0 -0.8526407 -0.5224978 0 -0.8526352 -0.5225067 0 -0.8686298 -0.4954618 0 -0.8686268 -0.495467 0 -0.8837708 -0.4679201 0 -0.8837735 -0.4679151 0 -0.8980237 -0.4399471 0 -0.8980215 -0.4399517 0 -0.9114012 -0.411519 0 -0.9114038 -0.4115134 0 -0.923883 -0.3826751 0 -0.9238827 -0.3826759 0 -0.9354417 -0.3534813 0 -0.9460888 -0.3239073 0 -0.9460887 -0.3239076 0 -0.9557924 -0.2940422 0 -0.9645547 -0.2638834 0 -0.9645531 -0.2638888 0 -0.9723742 -0.2334275 0 -0.9723712 -0.2334402 0 -0.9723793 -0.2334064 0 -0.9723742 -0.233428 7.91861e-7 2.73314e-6 0 -1 1.14738e-5 0 -1 -1.75505e-5 0 -1 1.14738e-5 0 -1 8.38245e-7 0 -1 5.46626e-6 0 -1 -3.3017e-5 0 -1 1.90748e-5 0 -1 -0.9723741 -0.2334282 0 -0.9723728 -0.2334335 0 -0.9723807 -0.2334008 0 -0.9723741 0.2334282 0 -0.9723728 0.2334335 0 -0.9723807 0.2334008 0 2.5273e-6 0 1 0 0 1 -2.52707e-6 0 1 3.10415e-6 0 1 2.52573e-6 0 1 -3.10761e-6 0 1 -1.16461e-6 0 1 1.35685e-6 0 1 -2.67183e-6 0 1 2.5226e-6 0 1 -2.42968e-6 0 1 3.10507e-6 0 1 3.79101e-6 0 1 -3.10097e-6 0 1 -4.95637e-6 0 1 3.10536e-6 0 1 2.52511e-6 0 1 -1.55421e-6 0 1 2.52237e-6 0 1 -1.55507e-6 0 1 1.26009e-6 0 1 -1.21324e-6 0 1 2.52588e-6 0 1 -7.76849e-7 0 1 -7.75615e-7 0 1 2.50208e-6 0 1 -3.88637e-7 0 1 -4.96384e-6 0 1 0 0 1 4.96384e-6 0 1 -2.50208e-6 0 1 7.76608e-7 0 1 -2.52588e-6 0 1 1.21324e-6 0 1 -1.26009e-6 0 1 -2.52237e-6 0 1 -2.52511e-6 0 1 4.95637e-6 0 1 6.20558e-6 0 1 -3.79101e-6 0 1 -6.22087e-6 0 1 6.22079e-6 0 1 1.33598e-6 0 1 -6.21787e-6 0 1 3.10619e-6 0 1 -3.10097e-6 0 1 2.42968e-6 0 1 2.67183e-6 0 1 -2.5226e-6 0 1 -1.35685e-6 0 1 1.16461e-6 0 1 -2.52573e-6 0 1 -1.50276e-6 0 1 2.52707e-6 0 1 -2.5273e-6 0 1 -3.10415e-6 0 1 3.10761e-6 0 1 -3.10507e-6 0 1 -3.10619e-6 0 1 6.21787e-6 0 1 2.67156e-6 0 1 -1.35779e-6 0 1 -6.22079e-6 0 1 -6.98128e-6 0 1 6.22087e-6 0 1 -6.21976e-6 0 1 6.22115e-6 0 1 -3.1728e-6 0 1 3.10097e-6 0 1 -3.10536e-6 0 1 1.55421e-6 0 1 1.55507e-6 0 1 7.76849e-7 0 1 -6.20632e-6 0 1 -9.18408e-7 0 1 7.75615e-7 0 1 3.88637e-7 0 1 0 0 1 -7.76608e-7 0 1 6.20632e-6 0 1 3.10097e-6 0 1 9.18408e-7 0 1 -6.22115e-6 0 1 6.21976e-6 0 1 -1.33598e-6 0 1 3.1728e-6 0 1 -1.16596e-6 0 1 1.50276e-6 0 1 -6.20558e-6 0 1 -2.67156e-6 0 1 6.98128e-6 0 1 1.35779e-6 0 1 -0.9792208 0.2027972 0 -0.9792225 0.202789 0 -0.9792208 -0.2027972 0 -0.9792225 -0.202789 0 -0.9792212 -0.2027953 0 -0.9792221 -0.2027909 0 -0.9851094 -0.1719288 0 -0.9851094 -0.171929 0 -0.9900228 -0.1409075 0 -0.9900235 -0.140903 0 -0.9939606 -0.1097376 0 -0.9939617 -0.1097284 0 -0.9969165 -0.07846987 0 -0.9969173 -0.07846063 0 -0.9988904 -0.047095 0 -0.9988902 -0.04709964 0 -0.9998765 -0.01571542 0 -0.9998767 -0.01571071 0 -0.9998767 0.01571071 0 -0.9998765 0.01571542 0 -0.9988902 0.04709964 0 -0.9988904 0.047095 0 -0.9969173 0.07846063 0 -0.9969165 0.07846987 0 -0.9939617 0.1097284 0 -0.9939606 0.1097376 0 -0.9900235 0.140903 0 -0.9900228 0.1409075 0 -0.9851094 0.1719288 0 -0.9851094 0.171929 0 -0.9792222 0.2027908 0 -0.9792212 0.2027954 0 -0.239316 0.9709418 0 -0.239316 0.9709419 0 0 1 0 0.9927088 -0.1205378 0 0.239316 0.9709419 0 0.992709 -0.1205363 0 0.239316 0.9709418 0 0.9350162 -0.3546053 0 0.4647237 0.8854558 0 0.4647223 0.8854565 0 0.9350166 -0.3546041 0 0.6631226 0.7485108 0 0.8229843 -0.5680641 0 0.8229836 -0.5680653 0 0.8229831 0.568066 0 0.8229848 0.5680635 0 0.6631226 -0.7485108 0 0.9350162 0.3546053 0 0.9350166 0.3546041 0 0.4647222 -0.8854566 0 0.4647239 -0.8854557 0 0.9927088 0.1205378 0 0.992709 0.1205363 0 0.239316 -0.9709419 0 0.239316 -0.9709418 0 0 -1 0 -0.239316 -0.9709418 0 -0.239316 -0.9709419 0 -0.4647223 -0.8854565 0 -0.4647237 -0.8854558 0 -0.6631226 -0.7485108 0 -0.8229831 -0.568066 0 -0.8229848 -0.5680635 0 -0.9350166 -0.3546041 0 -0.9350162 -0.3546053 0 -0.992709 -0.1205363 0 -0.9927088 -0.1205378 0 -0.9927088 0.1205378 0 -0.992709 0.1205363 0 -0.9350166 0.3546041 0 -0.9350162 0.3546053 0 -0.8229836 0.5680653 0 -0.8229843 0.5680641 0 -0.6631226 0.7485108 0 -0.4647239 0.8854557 0 -0.4647222 0.8854566 0 -0.9851092 0.1719306 0 -0.9851098 0.1719264 0 -0.9900229 0.1409066 0 -0.9939617 0.1097279 0 -0.9939609 0.1097353 0 -0.9969164 0.0784704 0 -0.9969174 0.07845866 0 -0.9988904 0.04709643 0 -0.9988902 0.04710024 0 -0.9998767 0.01571047 0 -0.9998766 0.01571434 0 -0.9998766 -0.01571434 0 -0.9998766 -0.01571041 0 -0.9988902 -0.0471003 0 -0.9988904 -0.04709631 0 -0.9969174 -0.07845878 0 -0.9969165 -0.07847028 0 -0.9939617 -0.1097279 0 -0.9939609 -0.1097353 0 -0.9900229 -0.1409066 0 -0.9851092 -0.1719306 0 -0.9851098 -0.1719264 0 2.34429e-6 0 1 -2.52564e-6 0 1 1.33925e-5 0 1 -2.27617e-6 0 1 3.34811e-6 0 1 0 0 1 + + + + + + + + + + + + + + +

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

+
+
+
+ + + + -0.1740955 -0.118 0.1765804 -0.1990954 -0.133 0.1765111 -0.1740955 -0.133 0.1765804 -0.1990954 -0.097 0.1765111 -0.1700955 -0.1159999 0.1765915 -0.1700955 -0.118 0.1765915 -0.1810651 -0.097 0.1765611 -0.1990621 -0.133 0.1644999 -0.1700619 -0.133 0.1644999 -0.1701426 -0.133 0.1935915 -0.1741425 -0.133 0.1935804 -0.1741425 -0.118 0.1935804 -0.1701426 -0.118 0.1935915 -0.1700619 -0.1159999 0.1644999 -0.1810316 -0.097 0.1644999 -0.1990621 -0.097 0.1644999 -0.2137646 -0.08394157 0.1644999 -0.215 -0.0854547 0.1644999 -0.215 -0.135 0.1644999 -0.2129775 -0.08191061 0.1644999 -0.156 -0.135 0.1644999 -0.215 0.06344473 0.1644999 -0.2138486 0.06202107 0.1644999 -0.215 0.06999999 0.1644999 -0.2129718 0.06001931 0.1644999 -0.156 0.06999999 0.1644999 -0.215 0.06999999 0.1628538 -0.2859272 0.06999999 0.02095824 -0.2938067 0.06999999 0.02547836 -0.156 0.06999999 0.01699995 -0.2859272 0.06999999 0.01699995 -0.215 0.06557542 0.1628538 -0.215 0.06455594 0.1637561 -0.2177773 0.06880331 0.1580124 -0.2187467 0.06899499 0.1563224 -0.2913336 0.06898951 0.1981401 -0.290196 0.06872189 0.2001503 -0.216845 0.06823575 0.1596377 -0.2891605 0.06798499 0.2019762 -0.2158459 0.06711989 0.1613792 -0.2882143 0.0667954 0.2036153 -0.2874261 0.06522089 0.204979 -0.2868186 0.06333553 0.2060033 -0.2864482 0.06121468 0.2066475 -0.2863444 0.05898648 0.2068721 -0.2863231 -0.08099734 0.2068643 -0.2864328 -0.08323144 0.206638 -0.2868157 -0.08533197 0.2060092 -0.215 -0.08656591 0.1637561 -0.2874203 -0.08721745 0.2049881 -0.215 -0.08758538 0.1628538 -0.2882057 -0.08879345 0.2036274 -0.2157098 -0.08892637 0.1616165 -0.2891435 -0.08999472 0.2019762 -0.216536 -0.08996373 0.1601763 -0.2176115 -0.09074121 0.1583015 -0.2902211 -0.09073519 0.2001422 -0.2187468 -0.09100496 0.1563224 -0.2913351 -0.0909779 0.1982477 -0.215 -0.135 0.1628538 -0.2938067 -0.135 0.02547836 -0.2859272 -0.135 0.02095824 -0.2859272 -0.135 0.01699995 -0.156 -0.135 0.01699995 -0.2913354 -0.08909517 0.02978616 -0.2921944 -0.08749943 0.02828884 -0.2928443 -0.08554488 0.02715599 -0.2903148 -0.09024375 0.03156524 -0.2932491 -0.08333945 0.02645027 -0.2893814 -0.0908128 0.03319245 -0.2933866 -0.08100497 0.0262106 -0.2884106 -0.09100496 0.03488469 -0.2930078 0.0628218 0.02687084 -0.2924363 0.06487286 0.02786719 -0.293291 0.06094586 0.02637726 -0.2933866 0.05899494 0.0262106 -0.2916423 0.06659907 0.02925133 -0.2906697 0.06790506 0.03094673 -0.2895723 0.06871867 0.0328598 -0.2884106 0.06899499 0.03488469 -0.361222 0.06899017 0.0770446 -0.2905374 0.06715452 0.2023406 -0.2895111 0.06622457 0.2038355 -0.2875952 0.06319898 0.20617 -0.2872369 0.06114757 0.2067903 -0.2899466 0.06570464 0.2037541 -0.2914828 0.06787049 0.2006558 -0.2908548 0.06847518 0.2004525 -0.2919642 0.06868135 0.1986386 -0.2925422 0.06806635 0.1988685 -0.2898597 0.06773436 0.2022478 -0.2881726 0.06503951 0.20517 -0.2908755 0.0663942 0.2023124 -0.2880932 0.06098783 0.2065746 -0.2879942 0.05889689 0.2067654 -0.2920728 0.06723332 0.2002366 -0.2882282 0.06300711 0.2060576 -0.2889401 0.06657713 0.2038403 -0.2886453 0.06037473 0.2061682 -0.2887621 0.06266355 0.2058057 -0.2889634 0.06462877 0.2050673 -0.2894391 0.06403213 0.2047897 -0.2871399 0.05903327 0.2069941 -0.2871306 -0.08095294 0.2070031 -0.2880021 -0.08104854 0.2067515 -0.2885464 -0.08238476 0.2062799 -0.3613013 -0.09098845 0.07699531 -0.2898657 -0.08975023 0.2022373 -0.2908914 -0.09046643 0.2004607 -0.2888051 -0.08485198 0.2057312 -0.2889795 -0.08667916 0.2050394 -0.2882282 -0.08501708 0.2060576 -0.2880581 -0.08303099 0.2065876 -0.2875981 -0.08522105 0.206165 -0.2871966 -0.08316868 0.2067887 -0.2895657 -0.08633196 0.2045765 -0.2889454 -0.08859544 0.2038313 -0.2888776 -0.08313715 0.2058057 -0.29152 -0.08985173 0.2006391 -0.292542 -0.09007632 0.1988687 -0.2903878 -0.08933621 0.2023171 -0.2881768 -0.08706009 0.2051628 -0.2916782 -0.08882164 0.2009553 -0.292089 -0.08938151 0.2001394 -0.2908512 -0.08885109 0.2021874 -0.2895111 -0.08823454 0.2038355 -0.2900238 -0.08783775 0.2036204 -0.2919742 -0.09070914 0.1985849 -0.3663129 0.05903738 0.0683422 -0.3661754 0.0612266 0.06855058 -0.3658207 0.06332594 0.06919687 -0.3652258 0.06521916 0.07022786 -0.3644352 0.0667997 0.07159805 -0.3634884 0.06798821 0.07323855 -0.3624372 0.068726 0.07507729 -0.3663244 -0.08097344 0.06834483 -0.3624377 -0.09073281 0.0750572 -0.3634913 -0.08999478 0.07323157 -0.3644382 -0.08880454 0.07159221 -0.3652287 -0.08722257 0.07022356 -0.3658233 -0.08532851 0.06919443 -0.3661923 -0.0832172 0.06855654 -0.3617912 0.06879693 0.07725095 -0.3622958 0.06838816 0.0775426 -0.3626002 0.06786274 0.07771807 -0.3634303 0.06732565 0.07658296 -0.3643353 0.06667512 0.0750904 -0.3664555 0.06275403 0.07140767 -0.3652729 0.0656082 0.0734477 -0.3668811 0.06036478 0.07065522 -0.3668379 -0.08263909 0.07075327 -0.3635542 -0.08920174 0.07642161 -0.3654192 -0.08738487 0.07319426 -0.3619746 -0.09070742 0.07734125 -0.362542 -0.09007048 0.07762533 -0.366595 0.06284254 0.07079887 -0.3660086 0.06476038 0.07133793 -0.3665145 0.06309419 0.07018214 -0.3669335 0.06102073 0.06997126 -0.3668196 0.05898171 0.06894892 -0.3670521 0.05894321 0.06981378 -0.3640697 0.0677402 0.07371211 -0.3630731 0.06843322 0.07550358 -0.3666769 0.06115877 0.06912511 -0.3660399 0.06447249 0.07195669 -0.3649901 0.06658542 0.07211816 -0.3635421 0.06781101 0.07591229 -0.3644722 0.06717652 0.07428222 -0.3657589 0.06505012 0.07078677 -0.3653333 0.06610095 0.0727908 -0.3662068 0.06324785 0.0696029 -0.3668364 -0.08100509 0.06898534 -0.3670507 -0.08100444 0.06985455 -0.3646086 -0.08876538 0.07443571 -0.3653535 -0.08807867 0.07275587 -0.3665199 -0.08508193 0.07017278 -0.3666986 -0.08315742 0.06915938 -0.3662068 -0.08525788 0.0696029 -0.3635379 -0.08984029 0.07590043 -0.3643999 -0.08933621 0.07412433 -0.3656229 -0.08711642 0.07061421 -0.3669397 -0.08299815 0.07000821 -0.36596 -0.08686941 0.07114291 -0.3649953 -0.0885871 0.07210904 -0.3666082 -0.08467441 0.07097196 -0.3640757 -0.08974438 0.07370167 -0.3661018 -0.08632719 0.07184934 -0.3630506 -0.09046339 0.07547736 -0.2939434 -0.06635516 0.03403133 -0.2938239 -0.0646857 0.03423821 -0.2936612 -0.06794422 0.03452003 -0.293042 -0.06908905 0.03559249 -0.2922278 -0.06952714 0.03700286 -0.291405 -0.06915807 0.03842794 -0.2935005 -0.06368404 0.03479832 -0.2907622 -0.06806647 0.03954118 -0.2931848 -0.06312453 0.03534525 -0.2928112 -0.06273239 0.03599226 -0.2924016 -0.06253051 0.03670173 -0.2904469 -0.06650251 0.04008722 -0.2919797 -0.06253051 0.03743243 -0.2904915 -0.06516736 0.04001009 -0.2906411 -0.06437844 0.03975099 -0.2915701 -0.06273239 0.0381419 -0.2911965 -0.06312453 0.03878897 -0.2908807 -0.06368404 0.0393359 -0.2887858 -0.06944626 0.03423064 -0.2895393 -0.06870067 0.03291732 -0.2867198 -0.06516647 0.03783226 -0.286669 -0.06600499 0.03792065 -0.2879464 -0.06940209 0.03569406 -0.286869 -0.06437683 0.03757214 -0.2871079 -0.06368196 0.0371555 -0.2872133 -0.0685783 0.0369718 -0.2874228 -0.06312239 0.03660666 -0.2877952 -0.06273078 0.03595751 -0.2867563 -0.06716972 0.03776842 -0.2882035 -0.0625298 0.03524583 -0.2886238 -0.06253129 0.03451317 -0.2890317 -0.06273508 0.03380209 -0.2894034 -0.0631293 0.03315412 -0.2897173 -0.06369102 0.03260689 -0.2899551 -0.06438755 0.0321924 -0.2901029 -0.06517821 0.03193467 -0.2901522 -0.06601709 0.03184878 -0.2900337 -0.0673362 0.03205549 -0.2239433 -0.06635516 0.1552749 -0.2238239 -0.0646857 0.1554818 -0.2236612 -0.0679441 0.1557636 -0.223042 -0.06908911 0.156836 -0.2222277 -0.06952714 0.1582464 -0.2207621 -0.06806647 0.1607848 -0.221405 -0.06915807 0.1596714 -0.2235005 -0.06368404 0.1560419 -0.2231848 -0.06312453 0.1565887 -0.2228112 -0.06273239 0.1572358 -0.2204915 -0.06516736 0.1612537 -0.2204469 -0.06650251 0.1613308 -0.2224016 -0.06253051 0.1579453 -0.2219797 -0.06253051 0.158676 -0.2215701 -0.06273239 0.1593855 -0.2206411 -0.06437844 0.1609946 -0.2208807 -0.06368404 0.1605795 -0.2211965 -0.06312453 0.1600325 -0.219122 -0.06944626 0.1556682 -0.2198755 -0.06870061 0.1543549 -0.2170559 -0.06516647 0.1592699 -0.2170051 -0.06600499 0.1593583 -0.2182825 -0.06940209 0.1571318 -0.2172051 -0.06437683 0.1590098 -0.2174441 -0.06368196 0.1585932 -0.2175495 -0.06857824 0.1584095 -0.217759 -0.06312239 0.1580443 -0.2181314 -0.06273078 0.1573952 -0.2170925 -0.0671696 0.1592061 -0.2185397 -0.0625298 0.1566835 -0.21896 -0.06253129 0.1559508 -0.2193679 -0.06273508 0.1552398 -0.2197396 -0.0631293 0.1545917 -0.2200534 -0.06369102 0.1540446 -0.2202913 -0.06438755 0.1536301 -0.2204391 -0.06517821 0.1533724 -0.2204884 -0.06601709 0.1532865 -0.2203698 -0.06733649 0.1534932 -0.2236612 0.04205584 0.1557636 -0.2239433 0.04364484 0.1552749 -0.223042 0.04091089 0.156836 -0.2238239 0.04531425 0.1554818 -0.2222277 0.0404728 0.1582464 -0.2214049 0.04084187 0.1596714 -0.2207621 0.04193347 0.1607848 -0.2235005 0.0463159 0.1560419 -0.2231848 0.04687541 0.1565887 -0.2228112 0.04726755 0.1572358 -0.2204915 0.04483258 0.1612537 -0.2204469 0.04349744 0.1613308 -0.2224016 0.04746943 0.1579453 -0.2219797 0.04746943 0.158676 -0.2215701 0.04726755 0.1593855 -0.2206411 0.04562151 0.1609946 -0.2211965 0.04687541 0.1600325 -0.2208807 0.0463159 0.1605795 -0.2191221 0.04055368 0.1556682 -0.2198755 0.04129934 0.1543549 -0.2170559 0.04483348 0.1592699 -0.2170051 0.04399496 0.1593583 -0.2182825 0.04059785 0.1571317 -0.2172051 0.04562318 0.1590098 -0.2174441 0.04631799 0.1585932 -0.2175495 0.04142171 0.1584095 -0.217759 0.04687756 0.1580443 -0.2181314 0.04726916 0.1573952 -0.2170925 0.04283034 0.1592061 -0.2185397 0.04747015 0.1566835 -0.21896 0.04746866 0.1559508 -0.2193679 0.04726487 0.1552398 -0.2197396 0.04687064 0.1545917 -0.2200534 0.04630893 0.1540446 -0.2202913 0.04561239 0.1536301 -0.2204391 0.04482173 0.1533724 -0.2204884 0.04398286 0.1532865 -0.2203698 0.04266351 0.1534932 -0.2939434 0.04364478 0.03403133 -0.2938239 0.04531425 0.03423821 -0.2936612 0.04205572 0.03452003 -0.293042 0.04091089 0.03559249 -0.2922278 0.0404728 0.03700286 -0.2914049 0.04084193 0.038428 -0.2935005 0.0463159 0.03479832 -0.2907622 0.04193347 0.03954118 -0.2931848 0.04687541 0.03534525 -0.2928112 0.04726755 0.03599226 -0.2924016 0.04746943 0.03670173 -0.2904469 0.04349744 0.04008722 -0.2919797 0.04746943 0.03743243 -0.2904915 0.04483258 0.04001009 -0.2906411 0.04562151 0.03975099 -0.2915701 0.04726755 0.0381419 -0.2911965 0.04687541 0.03878897 -0.2908807 0.0463159 0.0393359 -0.2887858 0.04055368 0.03423064 -0.2895393 0.04129928 0.03291732 -0.2867198 0.04483348 0.03783226 -0.286669 0.04399496 0.03792065 -0.2879464 0.04059785 0.03569406 -0.286869 0.04562318 0.03757214 -0.2871079 0.04631799 0.0371555 -0.2872133 0.04142165 0.0369718 -0.2874228 0.04687756 0.03660666 -0.2877952 0.04726916 0.03595751 -0.2867563 0.04283022 0.03776842 -0.2882035 0.04747015 0.03524583 -0.2886238 0.04746866 0.03451317 -0.2890317 0.04726487 0.03380209 -0.2894034 0.04687064 0.03315412 -0.2897173 0.04630893 0.03260689 -0.2899551 0.04561239 0.0321924 -0.2901555 0.04433351 0.03184306 -0.2900337 0.04266375 0.03205549 + + + + + + + + + + -0.002772808 0 0.9999962 -0.002771198 0 0.9999963 -0.002779364 0 0.9999961 -0.002773225 -1.60935e-6 0.9999962 -0.002780199 -1.87583e-6 0.9999961 0 -1 4.96729e-7 0 -1 0 0 -1 -4.68119e-7 -0.9999963 0 -0.002770721 -0.9999963 0 -0.002770721 0 1 0 0.9999963 0 0.002770662 0.9999963 2.13423e-6 0.002774119 0.9999962 0 0.002778947 0.9999962 0 0.002778947 0.8660219 0.5000005 0.002405881 0.8660221 0.4999998 0.002405583 -0.9999963 0 -0.002772748 -0.9999962 0 -0.002772748 -6.06656e-6 6.18805e-6 1 0 0 1 0 -5.16606e-6 1 4.9633e-5 3.65748e-6 1 0 0 1 0 -1.493e-6 1 6.52109e-7 0 1 -2.58459e-6 0 1 -0.00277841 0 0.9999962 -0.002770662 0 0.9999962 0 1 0 -1 0 0 0.04881227 0.9951962 0.08486473 0.05703967 0.9933565 0.09994798 0.1649159 0.9435483 0.2872619 0.1450007 0.9570515 0.2510527 0.2654021 0.8466474 0.4612483 0.2431839 0.8740726 0.4205459 0.3528567 0.7072403 0.6126201 0.3364761 0.7401412 0.5822156 0.4219233 0.5340047 0.7326799 0.396809 0.6083553 0.6873475 0.4322718 0.5016412 0.7493312 0.4710779 0.3306623 0.8177703 0.4634482 0.3748186 0.802949 0.4886603 0.2140167 0.8458179 0.4959009 0.109932 0.8613926 0.5001607 -2.02055e-5 0.8659326 0.5000923 2.81109e-5 0.8659722 0.4959932 -0.1115815 0.8611274 0.4910745 -0.1903229 0.8500724 0.4709932 -0.3306783 0.8178126 0.4628286 -0.3778744 0.8018732 0.4223628 -0.5326348 0.7334234 0.4322592 -0.5016366 0.7493416 0.3534719 -0.705982 0.6137158 0.3968089 -0.608353 0.6873494 0.2669025 -0.845077 0.4632579 0.3424225 -0.7286055 0.5931956 0.2646332 -0.8480836 0.4590464 0.1640795 -0.9444168 0.2848771 0.1691709 -0.940981 0.2931485 0.05462807 -0.9939556 0.09522718 0.05727863 -0.9933832 0.0995444 -1 -6.54613e-7 0 0 -1 -6.47353e-7 0 -1 1.99034e-7 1 0 0 -0.4975949 0 -0.8674096 -0.4975945 0 -0.8674098 -0.8674005 1.33554e-6 0.4976109 -0.8673966 1.70273e-6 0.4976177 -0.867403 -2.33163e-6 0.4976063 -0.8674384 0 0.4975446 -0.8674272 1.0589e-5 0.4975641 -0.8673703 -3.44632e-6 0.4976635 -0.8673975 -5.29674e-6 0.4976159 -0.8674085 1.73762e-6 0.4975969 -0.8674085 0 0.4975968 -0.8674153 -2.27451e-6 0.4975849 -0.8674081 2.33435e-6 0.4975976 -0.8674042 1.49293e-6 0.4976044 -0.8674202 -2.01802e-5 0.4975763 -0.8673763 -4.10109e-6 0.4976529 -0.8674088 7.73735e-6 0.4975963 -0.8674071 0 0.4975991 -0.8674108 1.79997e-5 0.4975929 -0.8674103 -1.88861e-5 0.4975938 -0.8674098 0 0.4975945 -0.8674024 0 0.4976072 -0.8674173 0 0.4975814 -0.8673953 -2.27393e-5 0.4976198 -0.867417 9.68309e-5 0.497582 -0.8674058 -1.02686e-4 0.4976016 -0.8673927 0 0.4976243 -0.8673911 0 0.4976272 -0.867407 -1.28727e-4 0.4975994 -0.8674088 5.29534e-5 0.4975962 0 0 -1 -4.97746e-5 1 2.86218e-5 -5.44046e-5 1 3.6736e-5 -0.6138337 0.4084788 0.6755392 -0.5548059 0.7176766 0.420869 -0.5780503 0.7000076 0.4193415 -0.4931499 0.6659707 0.5597198 -0.480871 0.6838669 0.548716 0.09733116 0.498524 0.8613945 0.09892827 0.4994937 0.8606505 -0.7293071 0.3015632 0.6141424 -0.7567823 0.3293564 0.5646283 -0.7603664 0.3171405 0.5668022 -0.7739562 0.3870773 0.5011618 -0.2404013 0.242262 0.9399555 -0.2768176 0.220972 0.9351702 0.03219634 0.6634832 0.7474982 0.03060632 0.6625171 0.7484213 -0.6220143 0.04187422 0.7818855 -0.5124148 0.1807206 0.8395065 -0.277713 0.4058077 0.8707444 -0.3093842 0.377199 0.8729275 -0.05078929 0.793763 0.606103 -0.04967075 0.794469 0.6052701 -0.7950279 0.05515402 0.6040602 -0.6509247 0.08625572 0.7542262 -0.5390286 0.2473036 0.8051641 -0.3580129 0.490452 0.7945336 -0.3273818 0.519298 0.789399 0.1566607 0.1018327 0.9823887 0.1684854 0.1066207 0.9799208 -0.1441569 0.8840147 0.4446761 -0.133797 0.8903391 0.435195 -0.2333207 0.9378479 0.2569101 -0.2508 0.9326446 0.2593715 -0.6689844 0.200407 0.7157493 -0.5748879 0.3671254 0.7312475 0.1469745 0.3108842 0.9390153 0.1439846 0.3093793 0.939975 -0.4209778 0.6007404 0.679624 -0.3962388 0.6325269 0.6655107 -0.8107435 0.1100416 0.5749659 -0.2690097 0.07485181 0.9602245 -0.68421 0.2223839 0.6945517 -0.2576563 0.08093196 0.9628412 0.1515617 7.41404e-5 0.9884478 0.1694182 -2.87416e-5 0.9855443 -0.2586142 4.54891e-5 0.9659808 -0.2772785 -7.92079e-5 0.9607896 -0.6757457 1.0864e-4 0.7371349 -0.6548053 -3.74049e-5 0.7557977 -0.819753 -1.19498e-4 0.5727174 -1.70511e-4 -1 9.77532e-5 -2.42149e-4 -1 2.26663e-4 -0.5303986 -0.2554656 0.8083407 -0.2693911 -0.07180356 0.9603503 -0.2359212 -0.2316663 0.9437542 -0.2563431 -0.2348065 0.9376322 -0.2395188 -0.08643335 0.9670367 -0.6779772 -0.2028162 0.7065498 -0.05044353 -0.794722 0.604874 -0.046166 -0.7951108 0.6047046 -0.7966515 -0.05981576 0.601472 -0.5225906 -0.1777839 0.8338417 -0.6266608 -0.1059938 0.7720503 -0.5797023 -0.05089128 0.8132376 -0.7710416 -0.06017464 0.6339352 -0.4662839 -0.6937341 0.5489194 -0.5020269 -0.6715036 0.5450249 0.02869457 -0.6630559 0.7480197 0.03483372 -0.6629992 0.7478093 -0.7689704 -0.4042674 0.4952299 -0.6574741 -0.4708206 0.5882651 -0.3905736 -0.6231635 0.6775836 -0.3920578 -0.6224753 0.677359 0.1008046 -0.4986289 0.8609342 0.0951004 -0.499252 0.8612221 -0.8168205 -0.1929746 0.543659 -0.7633298 -0.3398808 0.5493712 -0.6244987 -0.4206883 0.6580446 -0.6112866 -0.429609 0.664654 -0.3592621 -0.5022705 0.7865463 -0.3190581 -0.5095005 0.7991316 -0.2513888 -0.9307518 0.2655276 0.1839181 -0.1079909 0.9769914 0.159552 -0.3096891 0.9373558 -0.2476593 -0.9318971 0.2650151 0.1632511 -0.0998494 0.9815189 0.1425587 -0.3132227 0.9389189 -0.8290717 -0.0973826 0.5505967 -0.8267947 -0.1060787 0.552411 -0.5847314 -0.3620394 0.7259592 -0.2763615 -0.3913953 0.8777437 -0.1408761 -0.8865172 0.4407281 -0.1454773 -0.885636 0.4410049 -0.3168597 -0.3871766 0.8658488 -0.6836173 -0.2314947 0.6921543 -0.5734823 -0.7031915 0.4202854 -0.5705487 -0.7053856 0.4206012 -0.4977933 0.09800404 -0.8617408 -0.4972922 0.1131188 -0.8601771 -0.4724645 0.3312743 -0.816722 -0.4784281 0.290286 -0.8287584 -0.4239321 0.5322413 -0.7328035 -0.4359542 0.4886007 -0.7557867 -0.3539514 0.7074115 -0.6117904 -0.3669348 0.6788147 -0.6360577 -0.2662159 0.847052 -0.4600347 -0.2776541 0.8314657 -0.4812204 -0.1648371 0.9443479 -0.2846679 -0.1730276 0.9381901 -0.2997682 -0.05694139 0.9935336 -0.09822815 -0.05884861 0.9930693 -0.1017363 -0.5002456 2.46416e-5 -0.8658837 -0.5002101 0 -0.8659041 -0.04920178 -0.9951846 -0.08477652 -0.05702239 -0.9935896 -0.0976122 -0.1659363 -0.9438195 -0.2857795 -0.1451146 -0.9569415 -0.2514056 -0.266759 -0.8465851 -0.4605794 -0.244011 -0.872497 -0.4233291 -0.3542588 -0.7067976 -0.6123217 -0.3391771 -0.7343284 -0.5879802 -0.4239805 -0.5315161 -0.7333015 -0.4156037 -0.5555697 -0.7201499 -0.4724222 -0.3295484 -0.8174443 -0.4690666 -0.346108 -0.8125182 -0.4971833 -0.1104664 -0.8605847 -0.496615 -0.1175317 -0.8599767 -0.2671092 0.9512545 0.1541674 -0.3127418 0.9324727 0.1807968 -0.4974266 0.8186888 0.2869071 -0.611949 0.707397 0.3537061 -0.7199663 0.5559498 0.4154136 -0.8335961 0.2711318 0.481254 -0.8214044 0.3165246 0.4744544 -0.8646428 0.05812698 0.4990132 -0.8642511 0.002028048 0.5030566 -0.8664413 -0.001198172 0.4992778 -0.8657726 1.37653e-4 0.5004376 -0.8713147 0.01033699 0.4906158 -0.8605201 -0.01060783 0.5093061 -0.865992 -0.002114534 0.5000535 -0.8647264 -0.00413084 0.5022264 -0.8660594 1.12535e-4 0.4999412 -0.8660435 8.14778e-5 0.4999686 -0.8660593 1.09971e-4 0.4999414 -0.8660935 -0.001590728 0.4998798 -0.8663393 -0.002076148 0.4994516 -0.3021145 -0.9371832 0.1743981 -0.3017331 -0.9373434 0.1741973 -0.6119329 -0.7076169 0.3532938 -0.6140845 -0.7051402 0.3545104 -0.8174626 -0.3301702 0.4719563 -0.8622104 -0.0930823 0.4979246 -0.8257257 -0.3018187 0.4765318 -0.955895 0.2936671 -0.004942595 -0.9638758 0.07440626 -0.2557482 -0.9435776 0.2161675 -0.2508646 -0.9572679 0.0851233 -0.2763915 -0.5495073 0.7945429 -0.2583478 -0.5493116 0.7945684 -0.2586848 -0.9579291 0.1543626 0.2419586 -0.9782844 0.2022895 -0.04515135 -0.7437793 0.5552964 0.3720732 -0.991469 0.04742664 0.1214087 -0.9668536 0.09794658 0.235798 -0.9793807 0.1029904 0.1738002 -0.728838 0.6687715 0.1467655 -0.7339189 0.6596515 0.1619358 -0.6312648 0.6636567 -0.4013286 -0.6317344 0.6636671 -0.4005718 -0.8218647 0.3874891 0.4176009 -0.7994725 0.6000055 0.02893763 -0.7986484 0.601254 0.02558493 -0.6715962 0.5058322 -0.5413802 -0.6950439 0.5073491 -0.5094222 -0.8668248 0.3445164 0.3604487 -0.8644252 0.3276132 0.3813644 -0.8577904 0.5090735 -0.0709927 -0.8470117 0.5199696 -0.1104665 -0.3018211 0.9515575 0.05867338 -0.8403791 0.427632 -0.3330075 -0.7681114 0.1015213 -0.6322171 -0.7552388 0.1089714 -0.6463279 -0.3719232 0.9247775 0.08037412 -0.7340923 0.3100154 -0.6041514 -0.7187834 0.3046737 -0.6249195 -0.9038347 0.2982671 0.3067895 -0.9003735 0.2847211 0.3290311 -0.9313874 0.3457726 0.1138381 -0.5333963 0.8163821 0.2213791 -0.4551825 0.8853142 -0.09501367 -0.4627031 0.8825256 -0.08399158 -0.8939773 0.4047756 -0.1922534 -0.875591 0.2860191 -0.3892729 -0.9125401 0.09347862 0.3981609 -0.9249013 0.2584455 0.2788613 -0.6739765 0.6868127 0.2721105 -0.9592997 0.2714566 0.0778166 -0.7810522 -6.84565e-5 -0.6244658 -0.7675159 5.11813e-5 -0.64103 -0.9709576 -7.94452e-5 -0.2392516 -0.9657296 4.88363e-5 -0.2595506 -0.9731591 -1.3592e-4 0.2301337 -0.9799839 4.7614e-5 0.199077 -0.8875045 -0.1214588 0.4445037 -0.9158349 -0.2728906 0.2945799 -0.8741831 -0.2872974 -0.3914899 -0.8251588 -0.3697784 0.4270561 -0.8430159 -0.4601336 0.2785701 -0.6723695 -0.5050549 -0.5411459 -0.6708002 -0.50589 -0.5423121 -0.8607108 -0.3350014 0.3833422 -0.9501919 -0.2096815 -0.2305842 -0.8378621 -0.4387232 -0.3248215 -0.8359272 -0.4406661 -0.3271682 -0.5993039 -0.6819005 -0.4193406 -0.6315225 -0.6631678 -0.4017311 -0.9868941 -0.04288858 0.1555655 -0.9801586 -0.198081 -0.007298767 -0.7858017 -0.5727033 -0.2335094 -0.5502222 -0.7937915 -0.2591341 -0.5491201 -0.7944064 -0.2595875 -0.9797732 -0.09146559 0.1779844 -0.348163 -0.9339299 0.08097916 -0.9605398 -0.2759878 0.03455728 -0.9580168 -0.2854549 0.02682375 -0.853524 -0.5167903 -0.06651729 -0.4557358 -0.8850072 -0.09522229 -0.4547476 -0.8854817 -0.09553438 -0.7747215 -0.1001053 -0.6243282 -0.3533738 -0.9318796 0.08202081 -0.9078376 -0.05774945 0.4153265 -0.7666285 -0.1049154 -0.6334617 -0.9079956 -0.05786418 0.4149647 -0.931394 -0.3540014 0.08478504 -0.8061509 -0.591426 0.01833677 -0.7830849 -0.6219148 1.30032e-4 -0.6500284 -0.7052783 0.2829236 -0.7187762 -0.3131419 -0.6207278 -0.7448667 -0.3002436 -0.5958418 -0.9281998 -0.2575969 0.2684945 -0.8755331 -0.4349039 0.2104773 -0.9684315 -0.07227021 -0.238574 -0.7274257 -0.6698722 0.1487388 -0.9626221 -0.08252078 -0.257971 -0.699316 -0.7008674 0.1405065 -0.6527778 -0.7026602 0.2831077 0.8660503 5.5046e-6 -0.499957 0.866028 -3.97297e-6 -0.4999958 0.8660274 0 -0.4999967 0.8660294 -1.76143e-4 -0.4999931 0.8659279 3.41602e-4 -0.5001688 0.8660488 1.16136e-4 -0.4999597 0.8660377 -1.51808e-4 -0.4999787 0.8660047 5.98013e-5 -0.5000359 0.8660312 0 -0.4999899 0.8660162 0 -0.5000159 0.8659608 -3.41636e-4 -0.5001118 0.8660352 0 -0.499983 0.8660216 0 -0.5000066 0.8660229 0 -0.5000045 0.8660216 1.29471e-5 -0.5000067 0.8660597 -7.51723e-6 -0.4999407 0.2012649 0.8969075 0.3937632 0.149375 0.9654331 0.2136027 -0.4963684 -0.1207225 -0.8596771 -0.03267413 0.9994008 -0.01142644 -0.4897617 -0.06653434 -0.869314 -0.4674866 -0.3549885 -0.8095923 -0.4674852 -0.3546094 -0.8097592 -0.08985555 0.9755116 -0.200757 -0.4113872 -0.5685747 -0.7123789 -0.2635828 0.8725333 -0.4113513 -0.4114505 -0.5680399 -0.7127687 -0.3313003 -0.749126 -0.5736291 -0.3314929 -0.7485157 -0.5743142 -0.3040151 0.7620455 -0.5717182 -0.2319449 -0.8860046 -0.401494 -0.4382215 0.5459892 -0.7140432 -0.2322679 -0.8854641 -0.4024984 -0.4440473 0.373811 -0.8143017 -0.1190742 -0.9712934 -0.2059381 -0.5066134 0.1490078 -0.8491994 -0.1195464 -0.9709397 -0.2073282 7.09735e-4 -0.9999986 0.00157833 1.33078e-4 -1 -6.91634e-5 0.1204549 -0.9704639 0.2090225 0.119818 -0.9709386 0.2071763 0.2331665 -0.8843964 0.4043221 0.2325351 -0.8854576 0.4023584 0.3322872 -0.7468345 0.5760412 0.3317639 -0.7484976 0.5741813 0.4191176 -0.5657212 0.7101409 0.4203345 -0.5424136 0.7273971 0.4586477 -0.3517164 0.8160502 0.5074326 -0.1416684 0.849966 0.503318 -0.1172273 0.8561126 0.4790229 0.1777308 0.8596214 0.4905816 0.3345538 0.804614 0.3845199 0.5885505 0.7111631 0.3588625 0.7340995 0.5764684 -0.8674513 2.2016e-5 0.4975224 -0.8675171 3.8744e-5 0.4974076 -0.8673946 1.29658e-5 0.4976211 -0.8673907 5.60026e-6 0.4976279 -0.8674302 0 0.4975591 -0.8674004 5.94379e-6 0.497611 -0.8674234 3.58929e-6 0.4975709 -0.8674076 -5.19508e-6 0.4975984 -0.8674179 -5.01051e-6 0.4975804 -0.8674141 7.47466e-6 0.497587 -0.8671472 -8.20773e-5 0.4980521 -0.8673668 1.05169e-5 0.4976696 -0.8674025 -1.00924e-5 0.4976073 -0.8674467 -2.20904e-5 0.4975302 -0.8673971 0 0.4976167 -0.8674175 1.99274e-5 0.4975811 -0.8674611 2.32951e-5 0.4975051 -0.8673927 9.04712e-6 0.4976244 0.8660583 2.20225e-5 -0.4999432 0.8660211 -7.94602e-6 -0.5000075 0.8660194 3.1784e-5 -0.5000104 0.8660232 -8.80754e-5 -0.5000039 0.8659482 1.70782e-4 -0.5001339 0.8660647 -7.6044e-5 -0.4999321 0.8659851 1.48336e-5 -0.50007 0.8659979 0 -0.5000478 0.8660363 1.1613e-4 -0.4999814 0.8662099 0 -0.4996806 0.8659366 -3.41693e-4 -0.5001538 0.86602 0 -0.5000094 0.8660223 0 -0.5000054 0.8660187 -1.22946e-5 -0.5000118 0.8660569 7.13313e-6 -0.4999455 0.8660319 4.92834e-5 -0.4999889 0.1993512 0.8968624 0.3948379 0.1512707 0.9653819 0.2124971 -0.4963884 -0.1206361 -0.8596776 -0.03458517 0.9993485 -0.01032084 -0.4888764 -0.06655031 -0.8698108 -0.4675054 -0.354988 -0.8095815 -0.4674804 -0.3545968 -0.8097674 -0.08793592 0.9754618 -0.2018457 -0.4113884 -0.5686158 -0.7123453 -0.2654921 0.8724714 -0.4102534 -0.4114509 -0.5680425 -0.7127664 -0.3313058 -0.7491319 -0.5736184 -0.3314743 -0.7485478 -0.5742831 -0.3020753 0.7620282 -0.5727683 -0.2319585 -0.8859978 -0.4015011 -0.4401234 0.5459572 -0.7128971 -0.2322672 -0.885456 -0.4025166 -0.4421212 0.3737821 -0.8153625 -0.1190871 -0.9712955 -0.205921 -0.507808 0.148953 -0.8484953 -0.1195287 -0.9709444 -0.2073163 6.94635e-4 -0.9999985 0.001593768 1.46072e-4 -1 -8.4598e-5 0.1204413 -0.9704564 0.2090656 0.1198266 -0.9709432 0.2071498 0.233137 -0.8844047 0.404321 0.23255 -0.8854547 0.4023563 0.3322796 -0.7468268 0.5760556 0.3317927 -0.7484707 0.5741997 0.4197705 -0.565722 0.7097545 0.4203702 -0.5424324 0.7273623 0.4577354 -0.3516652 0.8165844 0.5086466 -0.1416569 0.8492421 0.5039612 -0.1172481 0.8557314 0.4777573 0.1777479 0.8603218 0.492462 0.3345242 0.8034767 0.3826135 0.588539 0.7121999 0.36077 0.7340271 0.5753689 -0.8673496 0 0.4976994 -0.8674049 -4.84259e-6 0.4976029 -0.8674324 6.48392e-6 0.4975553 -0.8673843 -2.51977e-5 0.4976391 -0.8674051 -4.32958e-6 0.4976028 -0.8674023 -1.18875e-5 0.4976078 -0.8674412 0 0.4975396 -0.8673781 -2.59781e-6 0.4976497 -0.8674115 -1.002e-5 0.4975916 -0.8674154 2.49154e-6 0.4975846 -0.8673192 2.7374e-5 0.4977525 -0.8673829 -2.6292e-6 0.4976414 -0.8674104 1.00927e-5 0.4975935 -0.8674003 2.76115e-6 0.4976112 -0.8674257 6.94321e-6 0.4975669 -0.8673925 -2.84697e-6 0.4976246 -0.867388 1.16472e-5 0.4976326 -0.8673966 1.35706e-5 0.4976175 0.8659816 -2.20217e-5 -0.5000758 0.8660214 -3.17838e-5 -0.500007 0.8660235 1.62714e-5 -0.5000033 0.8660184 0 -0.5000122 0.8659573 1.70783e-4 -0.5001179 0.8660688 -7.60443e-5 -0.4999249 0.8659858 1.48336e-5 -0.5000686 0.866029 1.16132e-4 -0.4999939 0.8660237 2.20617e-5 -0.5000032 0.8660266 9.75052e-6 -0.4999982 0.8660228 -2.95689e-5 -0.5000046 0.8659924 1.1242e-5 -0.5000574 0.8659319 -3.41692e-4 -0.5001618 0.8660349 4.92828e-5 -0.4999836 0.8660092 -5.23213e-5 -0.5000282 0.1993522 0.8968594 0.3948442 0.1512703 0.9653826 0.2124945 -0.4963772 -0.1206334 -0.8596844 -0.03457915 0.9993488 -0.01030761 -0.488876 -0.06655102 -0.8698111 -0.4674988 -0.354983 -0.8095875 -0.4674823 -0.3545982 -0.8097655 -0.08793622 0.9754599 -0.2018543 -0.2654906 0.8724732 -0.4102504 -0.4114514 -0.5680493 -0.7127607 -0.3313052 -0.7491404 -0.5736075 -0.3314752 -0.7485499 -0.5742799 -0.3020771 0.7620328 -0.5727614 -0.2319543 -0.8859988 -0.4015015 -0.4401165 0.5459487 -0.7129078 -0.2322747 -0.8854512 -0.4025231 -0.4421228 0.3737834 -0.815361 -0.119085 -0.9712958 -0.2059211 -0.5078167 0.1489574 -0.8484893 -0.1195265 -0.9709439 -0.2073194 6.93823e-4 -0.9999985 0.001585125 1.45263e-4 -1 -8.56826e-5 0.1204372 -0.9704586 0.2090574 0.1198265 -0.9709428 0.2071519 0.2331419 -0.884407 0.4043135 0.2325488 -0.88545 0.4023672 0.3322779 -0.7468231 0.5760614 0.3317933 -0.748472 0.5741975 0.4197802 -0.5657234 0.7097476 0.4203613 -0.5424289 0.7273702 0.4577386 -0.3516677 0.8165814 0.5086455 -0.1416577 0.8492425 0.5039685 -0.1172498 0.8557267 0.4777512 0.1777496 0.8603249 0.4924597 0.3345247 0.803478 0.3826133 0.5885246 0.712212 0.3607776 0.7340294 0.5753611 -0.8673266 0 0.4977394 -0.8674072 -4.8426e-6 0.4975993 -0.8674283 0 0.4975623 -0.8673871 -2.51978e-5 0.497634 -0.8674234 4.32932e-6 0.4975708 -0.8673905 -5.944e-6 0.4976282 -0.8674362 5.38379e-6 0.4975487 -0.8673999 -2.59763e-6 0.4976117 -0.8674114 0 0.4975919 -0.8674167 -2.49155e-6 0.4975826 -0.867295 2.73767e-5 0.4977946 -0.8673721 -2.62929e-6 0.4976603 -0.8674154 1.00926e-5 0.4975848 -0.867403 2.76116e-6 0.4976062 -0.8674282 6.94301e-6 0.4975624 -0.8673914 -5.69394e-6 0.4976267 -0.8673881 1.3571e-5 0.4976323 0.866051 1.65139e-5 -0.4999558 0.866024 0 -0.5000026 0.8660279 0 -0.4999958 0.8660175 -8.80703e-5 -0.5000138 0.8659332 3.41595e-4 -0.5001595 0.8660559 1.16137e-4 -0.4999473 0.8660128 5.98018e-5 -0.5000219 0.8660336 0 -0.4999858 0.8660127 0 -0.5000221 0.8659641 -3.41654e-4 -0.5001063 0.8660515 0 -0.4999549 0.8660219 0 -0.5000063 0.8660238 0 -0.5000029 0.8660199 1.29471e-5 -0.5000097 0.8660593 -7.51722e-6 -0.4999414 0.2012692 0.8969059 0.3937645 0.1493749 0.9654307 0.2136137 -0.03266847 0.9994012 -0.01141047 -0.4897657 -0.06653505 -0.8693116 -0.4674791 -0.3549814 -0.8095996 -0.4674885 -0.3546104 -0.8097568 -0.08985686 0.9755097 -0.2007654 -0.4113825 -0.5685682 -0.7123866 -0.2635879 0.872532 -0.4113507 -0.4114581 -0.5680505 -0.7127559 -0.3312998 -0.7491338 -0.5736193 -0.3314932 -0.7485187 -0.5743101 -0.3040154 0.7620487 -0.5717137 -0.231947 -0.8860012 -0.4015004 -0.4382221 0.5459971 -0.7140368 -0.2322697 -0.8854578 -0.4025113 -0.4440428 0.3738105 -0.8143044 -0.119073 -0.9712935 -0.2059381 -0.5066142 0.1489877 -0.8492025 -0.119545 -0.9709419 -0.2073187 7.08997e-4 -0.9999986 0.001594126 1.32338e-4 -1 -7.80558e-5 0.1204506 -0.9704628 0.2090301 0.1198153 -0.9709405 0.2071688 0.2331696 -0.8843988 0.4043152 0.2325361 -0.8854544 0.4023649 0.3322874 -0.7468307 0.5760461 0.3317634 -0.7484966 0.5741829 0.4191183 -0.5657248 0.7101376 0.4203341 -0.5424131 0.7273977 0.4638733 -0.3003476 0.8334345 0.5143676 -0.1416392 0.8457922 0.4750258 0.1450621 0.8679329 0.4905845 0.3345526 0.8046127 0.3845227 0.5885457 0.7111654 0.3588606 0.7341015 0.576467 -0.8674879 4.42942e-5 0.4974584 -0.867394 0 0.4976222 -0.8673909 1.6801e-5 0.4976274 -0.8674306 0 0.4975582 -0.8673973 5.94387e-6 0.4976164 -0.8674224 3.58931e-6 0.4975725 -0.8674082 -1.55853e-5 0.4975972 -0.8674201 0 0.4975764 -0.8674154 2.49156e-6 0.4975849 -0.8671425 -5.47197e-5 0.4980601 -0.8673654 5.25848e-6 0.4976722 -0.8674049 -1.00923e-5 0.4976031 -0.867439 -3.3137e-5 0.4975435 -0.8673992 6.943e-6 0.497613 -0.8674181 1.42339e-5 0.49758 -0.8674585 2.32953e-5 0.4975095 -0.8673934 9.04713e-6 0.4976231 + + + + + + + + + + + + + + +

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

+
+
+
+
+ + + + + 0.6859207 -0.3240135 0.6515582 7.481132 0.7276763 0.3054208 -0.6141704 -6.50764 0 0.8953956 0.4452714 5.343665 0 0 0 1 + + + + -0.2908646 -0.7711008 0.5663932 4.076245 0.9551712 -0.1998834 0.2183912 1.005454 -0.05518906 0.6045247 0.7946723 5.903862 0 0 0 1 + + + + 1 0 0 0 0 1 0 0 0 0 1 0 0 0 0 1 + + + + + + + + + + 1 0 0 0 0 1 0 0 0 0 1 0 0 0 0 1 + + + + + + + + + + 1 0 0 0 0 1 0 0 0 0 1 0 0 0 0 1 + + + + + + + + + + 1 0 0 0 0 1 0 0 0 0 1 0 0 0 0 1 + + + + + + + + + + + + + +
\ No newline at end of file diff --git a/kuka_kr5_support/meshes/kr5_arc/visual/link_1.dae b/kuka_kr5_support/meshes/kr5_arc/visual/link_1.dae new file mode 100644 index 000000000..613964888 --- /dev/null +++ b/kuka_kr5_support/meshes/kr5_arc/visual/link_1.dae @@ -0,0 +1,645 @@ + + + + + Blender User + Blender 2.79.0 commit date:2017-09-11, commit time:10:43, hash:5bd8ac9abfa + + 2017-11-10T20:01:18 + 2017-11-10T20:01:18 + + Z_UP + + + + + + + 49.13434 + 1.777778 + 0.1 + 100 + + + + + + 0 + 0 + 0 + + + + + + + + + 1 1 1 + 1 + 0 + 0.00111109 + + + + + 0 + 0 + 8192 + 1 + 1 + 1 + 1 + 0 + 0 + 0 + 1 + 29.99998 + 75 + 0.15 + 1 + 0 + 1 + 2 + 1.000799 + 30.002 + 1 + 3 + 0.04999995 + 2880 + 3 + 1 + 0 + 0 + 2 + 1 + 1 + 1 + 0 + 1 + 0.1 + 0.1 + 1 + 0.000999987 + 1 + 0 + 0 + 1 + 1 + 1 + 1 + 1 + 1 + 1 + 2 + 1 + 1 + 1 + 1 + 0 + + + + + + + + + + + + 0 0 0 1 + + + 0 0 0 1 + + + 0.09803922 0.09803922 0.09803922 1 + + + 0.5 0.5 0.5 1 + + + 0 + + + 1 1 1 1 + + + 1 + + + + + + + + + + + 0 0 0 1 + + + 0 0 0 1 + + + 0.09803922 0.09803922 0.09803922 1 + + + 0.5 0.5 0.5 1 + + + 0 + + + 1 1 1 1 + + + 1 + + + + + + + + + + + 0 0 0 1 + + + 0 0 0 1 + + + 0.09803922 0.09803922 0.09803922 1 + + + 0.5 0.5 0.5 1 + + + 0 + + + 1 1 1 1 + + + 1 + + + + + + + + + + + 0 0 0 1 + + + 0 0 0 1 + + + 0.09803922 0.09803922 0.09803922 1 + + + 0.5 0.5 0.5 1 + + + 0 + + + 1 1 1 1 + + + 1 + + + + + + + + + + + 0 0 0 1 + + + 0 0 0 1 + + + 0.09803922 0.09803922 0.09803922 1 + + + 0.5 0.5 0.5 1 + + + 0 + + + 1 1 1 1 + + + 1 + + + + + + + + + + + 0 0 0 1 + + + 0 0 0 1 + + + 0.09803922 0.09803922 0.09803922 1 + + + 0.5 0.5 0.5 1 + + + 0 + + + 1 1 1 1 + + + 1 + + + + + + + + + + + 0 0 0 1 + + + 0 0 0 1 + + + 1 0.4980392 0 1 + + + 0.5 0.5 0.5 1 + + + 0 + + + 1 1 1 1 + + + 1 + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + 0.181037 0.03297728 0.2221246 0.1779171 0.03274267 0.2216291 0.179365 0.0134865 0.2216291 0.1824849 0.0137211 0.2221246 0.1751026 0.03253102 0.220191 0.1765505 0.01327484 0.220191 0.179365 0.0134865 0.2023709 0.1743169 0.01310694 0.2060489 0.1765505 0.01327484 0.203809 0.1728829 0.01299911 0.2088713 0.1723887 0.01296192 0.212 0.1856048 0.01395565 0.2023709 0.1824849 0.0137211 0.2018754 0.1743169 0.01310694 0.2179511 0.1728829 0.01299911 0.2151287 0.1920869 0.01444303 0.2088713 0.1884193 0.0141673 0.203809 0.1906528 0.01433521 0.2060489 0.1856048 0.01395565 0.2216291 0.1906528 0.01433521 0.2179511 0.1925809 0.01448023 0.212 0.1920869 0.01444303 0.2151287 0.1884193 0.0141673 0.220191 0.1869714 0.03342348 0.220191 0.189205 0.03359138 0.2179511 0.1841568 0.03321182 0.2216291 0.190639 0.03369921 0.2151287 0.1911331 0.0337364 0.212 0.190639 0.03369921 0.2088713 0.189205 0.03359138 0.2060489 0.172869 0.03236311 0.2179511 0.1714349 0.03225529 0.2151287 0.1869714 0.03342348 0.203809 0.1841568 0.03321182 0.2023709 0.181037 0.03297728 0.2018754 0.1709408 0.03221809 0.212 0.1714349 0.03225529 0.2088713 0.1779171 0.03274267 0.2023709 0.1751026 0.03253102 0.203809 0.172869 0.03236311 0.2060489 0.1841568 -0.03321182 0.2216291 0.1856048 -0.01395565 0.2216291 0.1824849 -0.0137211 0.2221246 0.181037 -0.03297728 0.2221246 0.1920869 -0.01444303 0.2088713 0.1906528 -0.01433521 0.2060489 0.1884193 -0.0141673 0.203809 0.1920869 -0.01444303 0.2151287 0.1925809 -0.01448023 0.212 0.1765505 -0.01327484 0.203809 0.1824849 -0.0137211 0.2018754 0.179365 -0.0134865 0.2023709 0.1856048 -0.01395565 0.2023709 0.1906528 -0.01433521 0.2179511 0.1884193 -0.0141673 0.220191 0.1723887 -0.01296192 0.212 0.1743169 -0.01310694 0.2060489 0.1728829 -0.01299911 0.2088713 0.179365 -0.0134865 0.2216291 0.1743169 -0.01310694 0.2179511 0.1728829 -0.01299911 0.2151287 0.1765505 -0.01327484 0.220191 0.1779171 -0.03274267 0.2216291 0.1869714 -0.03342348 0.220191 0.190639 -0.03369921 0.2151287 0.189205 -0.03359138 0.2179511 0.190639 -0.03369921 0.2088713 0.1911331 -0.0337364 0.212 0.1751026 -0.03253102 0.220191 0.1869714 -0.03342348 0.203809 0.189205 -0.03359138 0.2060489 0.1841568 -0.03321182 0.2023709 0.1714349 -0.03225529 0.2151287 0.172869 -0.03236311 0.2179511 0.1709408 -0.03221809 0.212 0.1779171 -0.03274267 0.2023709 0.181037 -0.03297728 0.2018754 0.172869 -0.03236311 0.2060489 0.1714349 -0.03225529 0.2088713 0.1751026 -0.03253102 0.203809 + + + + + + + + + + -0.1559817 -0.01172882 0.9876904 -0.155977 -0.01172882 0.9876911 -0.4527079 -0.03403985 0.8910089 -0.4527302 -0.03403925 0.8909976 0.07497471 -0.9971855 4.69281e-6 0.07497388 -0.9971855 -5.65987e-6 0.07497811 -0.9971852 -8.50179e-7 0.0749799 -0.9971851 -1.40803e-5 0.07498055 -0.997185 -2.93328e-7 0.07498008 -0.9971851 9.66055e-7 0.07498735 -0.9971845 -4.6936e-6 0.0749731 -0.9971856 4.85116e-6 0.07497864 -0.9971852 2.5043e-6 0.07497882 -0.9971851 2.51245e-7 0.07497984 -0.9971851 -4.69299e-6 0.07497841 -0.9971852 -3.91324e-7 0.07498222 -0.9971849 -3.23409e-6 0.0749762 -0.9971854 -1.58628e-6 0.07497596 -0.9971854 -2.93262e-7 0.07497775 -0.9971853 0 0.07498055 -0.9971851 3.57761e-7 0.07497096 -0.9971858 -1.40782e-5 -0.07496911 0.9971859 9.38581e-6 -0.07496899 0.997186 7.03962e-6 -0.07497239 0.9971857 -7.03989e-6 -0.07498168 0.997185 0 -0.07497191 0.9971857 -9.38616e-6 -0.0749793 0.9971852 0 -0.07497614 0.9971854 -6.46834e-6 -0.07496911 0.9971859 -9.38581e-6 -0.07497739 0.9971852 0 -0.07497853 0.9971852 0 -0.07498002 0.9971851 0 -0.07497853 0.9971852 0 -0.07497686 0.9971853 0 -0.07495665 0.9971868 0 -0.07498079 0.997185 0 -0.07498174 0.9971849 -9.38562e-6 -0.07497531 0.9971854 3.79366e-6 -0.07497894 0.9971852 0 0.1559848 0.01172858 0.9876899 0.1559817 0.01172858 0.9876904 -0.7051103 -0.05301797 0.7071129 -0.7051166 -0.05301785 0.7071067 0.452718 0.03403943 0.8910039 0.4526991 0.0340408 0.8910135 0.7051313 0.05301886 0.7070919 0.7051178 0.05301457 0.7071057 0.8885056 0.06680309 0.4539771 0.8884892 0.06680852 0.4540084 0.9849109 0.07405638 0.1564171 0.9849102 0.07405781 0.1564204 0.9849102 0.07405781 -0.1564204 0.9849105 0.07405579 -0.1564198 0.8884897 0.0668084 -0.4540075 0.8885025 0.06680399 -0.4539832 0.7051178 0.05301457 -0.7071056 0.7051319 0.05301976 -0.7070912 0.4527087 0.03404062 -0.8910085 0.452718 0.03403949 -0.8910039 0.1559854 0.0117281 -0.9876898 0.1559669 0.01172834 -0.9876927 -0.1559788 -0.01172858 -0.9876908 -0.1559817 -0.01172858 -0.9876904 -0.4527043 -0.03403973 -0.8910108 -0.4527079 -0.03403985 -0.8910089 -0.7051184 -0.05301767 -0.7071048 -0.7051178 -0.05301839 -0.7071053 -0.8885024 -0.06680953 -0.4539824 -0.8885053 -0.06680685 -0.4539771 -0.9849053 -0.0740574 -0.1564521 -0.9849057 -0.07405459 -0.1564505 -0.9849053 -0.07405567 0.1564527 -0.9849057 -0.07405632 0.1564497 -0.8885021 -0.0668078 0.4539831 -0.8885033 -0.06680929 0.4539807 0.1559847 -0.01172858 0.9876899 0.1559818 -0.01172858 0.9876903 0.07498735 0.9971845 -4.6936e-6 0.07497465 0.9971855 0 0.07498276 0.9971849 2.34644e-6 0.07497644 0.9971853 -2.42574e-6 0.0749787 0.9971852 -1.27524e-6 0.07498067 0.997185 3.57754e-7 0.07497823 0.9971852 0 0.07496863 0.997186 -1.40782e-5 0.07498121 0.9971849 5.46868e-7 0.07498174 0.997185 0 0.07497471 0.9971855 -3.23432e-6 0.07497715 0.9971854 -8.95575e-7 0.07497847 0.9971852 0 0.07497739 0.9971852 1.40798e-5 0.07498055 0.997185 -2.93328e-7 0.07497745 0.9971853 2.41514e-6 0.07497984 0.9971851 -3.23419e-6 0.07497692 0.9971854 -1.70031e-6 -0.155977 0.01172882 0.9876911 -0.1559817 0.01172882 0.9876904 0.4526991 -0.0340408 0.8910135 0.452718 -0.03403949 0.8910039 -0.07497847 -0.9971852 -4.6929e-6 -0.07497948 -0.9971851 -2.55047e-6 -0.07497406 -0.9971855 4.85122e-6 -0.07499843 -0.9971837 0 -0.07497811 -0.9971852 0 -0.07497811 -0.9971852 9.38576e-6 -0.07498151 -0.997185 9.38545e-6 -0.07497835 -0.9971852 3.91326e-7 -0.07497727 -0.9971853 -9.70276e-6 -0.07497751 -0.9971853 0 -0.0749787 -0.9971852 -7.15504e-7 -0.07498967 -0.9971843 4.8515e-6 -0.0749787 -0.9971852 -2.51245e-7 -0.07498115 -0.9971851 4.69336e-6 -0.07500022 -0.9971836 -4.6936e-6 -0.07497876 -0.9971852 0 -0.07497727 -0.9971852 0 -0.07497191 -0.9971857 9.38616e-6 -0.4527302 0.03403925 0.8909976 -0.4527079 0.03403985 0.8910089 -0.7051166 0.05301785 0.7071067 -0.7051103 0.05301797 0.7071129 -0.8885033 0.06680929 0.4539807 -0.8885021 0.0668078 0.4539832 -0.9849053 0.07405567 0.1564527 -0.9849057 0.07405632 0.1564497 -0.9849057 0.07405459 -0.1564505 -0.9849053 0.0740574 -0.1564521 -0.8885024 0.06680953 -0.4539824 -0.8885054 0.06680691 -0.4539771 -0.7051184 0.05301767 -0.7071048 -0.705118 0.05301839 -0.7071053 -0.4527043 0.03403973 -0.8910108 -0.4527079 0.03403985 -0.8910089 -0.1559788 0.01172858 -0.9876908 -0.1559891 0.01172858 -0.9876892 0.1559854 -0.0117281 -0.9876898 0.1559743 -0.01172834 -0.9876915 0.4527087 -0.03404062 -0.8910085 0.4527119 -0.03403955 -0.891007 0.7051319 -0.05301976 -0.7070912 0.7051178 -0.05301457 -0.7071057 0.8884897 -0.0668084 -0.4540075 0.8885025 -0.06680399 -0.4539832 0.9849105 -0.07405579 -0.1564198 0.9849102 -0.07405781 -0.1564204 0.9849109 -0.07405638 0.1564171 0.9849102 -0.07405781 0.1564204 0.8884892 -0.06680852 0.4540084 0.8885056 -0.06680309 0.4539771 0.7051313 -0.05301886 0.7070919 0.7051178 -0.05301457 0.7071056 + + + + + + + + + + + + + + +

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

+
+
+
+ + + + 0.1811296 0.2484706 -0.02772039 0.18 0.2537233 -0.0249601 0.1863999 0.2524501 -0.0249601 0.1907068 0.241435 0.02773267 0.1858788 0.2369989 0.02942419 0.1914805 0.237 0.02771633 0.1918251 0.2488252 -0.0249601 0.1949999 0.252 -0.02121317 0.197638 0.2487854 -0.02121317 0.1841385 0.2578056 0.02121317 0.18 0.2582132 0.02121317 0.18 0.2537233 0.0249601 0.1863999 0.2524502 0.0249601 0.1788509 0.2428008 -0.02944362 0.176654 0.2480297 -0.02772045 0.1569547 0.2523984 0.01148045 0.1543934 0.2476066 0.01148045 0.1580013 0.2487586 0.01666706 0.160718 0.2528244 0.01666706 0.1864383 0.246636 -0.02773267 0.1550559 0.2203329 0 0.1587868 0.2157868 0 0.1572553 0.2183338 0.005852699 0.1954501 0.2433999 -0.0249601 0.1540507 0.2231298 0.005852699 0.1854072 0.2098162 -0.01148045 0.1885412 0.2088434 -0.005852699 0.182884 0.2077181 -0.005852699 0.1995984 0.2451179 -0.02121317 0.1906065 0.2113934 -0.01148045 0.2008056 0.2328615 -0.02121317 0.204925 0.2354409 -0.0166791 0.2038699 0.229759 -0.01666706 0.2012132 0.237 -0.02121317 0.1918252 0.2488252 0.02496004 0.2008056 0.2411385 -0.02121317 0.1727591 0.26087 0.01666706 0.1682414 0.2589987 0.01666706 0.171882 0.2565984 0.02121317 0.1758615 0.2578056 0.02121317 0.1967242 0.2369999 -0.02495956 0.150718 0.239884 0.005852699 0.150718 0.234116 0.005852699 0.1522836 0.237 0.01148045 0.1528162 0.2424072 0.01148045 0.1914805 0.237 -0.02771633 0.1822693 0.2424225 -0.02942407 0.1661298 0.2110507 -0.005852699 0.1685194 0.2092836 0 0.1633329 0.2120559 0 0.1714588 0.2088434 -0.005852699 0.1958244 0.217718 -0.01666706 0.1995984 0.2174016 -0.01148045 0.1953984 0.2139547 -0.01148045 0.1907068 0.241435 -0.02773267 0.199282 0.2211756 -0.01666706 0.1881179 0.2565984 0.02121317 0.1845912 0.2407308 -0.02942615 0.1604016 0.2565984 0.01148045 0.1641756 0.256282 0.01666706 0.1522836 0.2255195 0 0.1518434 0.2284588 0.005852699 0.18 0.2092836 -0.01148045 0.177116 0.2077181 -0.005852699 0.1859192 0.237082 -0.02942728 0.1995984 0.2288821 -0.02121317 0.2019987 0.2252414 -0.01666706 0.1821258 0.2365509 0.02993535 0.1954501 0.2433999 0.0249601 0.1846572 0.233178 0.02943384 0.1775551 0.261824 0.01666706 0.1518434 0.2455412 0.005852699 0.1613339 0.2142553 -0.005852699 0.1815541 0.2345005 0.02987581 0.1917586 0.2150013 -0.01666706 0.1917853 0.2546381 0.02121317 0.1646016 0.2600453 0.01148045 0.1505764 0.2311473 0 0.1745927 0.2098162 -0.01148045 0.197638 0.2252146 -0.02121317 0.1824449 0.261824 0.01666706 0.1540507 0.2508702 0.005852699 0.1572553 0.2183338 -0.005852699 0.1872408 0.2131299 -0.01666706 0.1805887 0.23109 0.02941936 0.1949999 0.252 0.02121317 0.1693934 0.2626066 0.01148045 0.15 0.237 0 0.1693934 0.2113934 -0.01148045 0.1910297 0.2336542 0.02772045 0.1949999 0.222 -0.02121317 0.1967242 0.237 0.02495956 0.2012132 0.237 0.02121317 0.1872408 0.26087 0.01666706 0.1572553 0.2556661 0.005852699 0.1812467 0.2396366 0.02987366 0.1806089 0.2429087 0.02941936 0.1540507 0.2231298 -0.005852699 0.18891 0.2296882 0.02772039 0.1824449 0.212176 -0.01666706 0.1954501 0.2306001 -0.0249601 0.197638 0.2487854 0.02121317 0.1846579 0.2407813 0.02944082 0.1745927 0.2641838 0.01148045 0.1505764 0.2428527 0 0.1954501 0.2306001 0.0249601 0.1854333 0.2268348 0.02772039 0.1646016 0.2139547 -0.01148045 0.1820932 0.237533 0.02993935 0.1917853 0.2193619 -0.02121317 0.1917586 0.2589987 0.01666706 0.1613339 0.2597447 0.005852699 0.1821258 0.2365509 -0.02993535 0.1518434 0.2284588 -0.005852699 0.1846174 0.2331693 -0.02944087 0.1775551 0.212176 -0.01666706 0.1918252 0.2251748 0.02496004 0.181554 0.2345005 -0.02987581 0.1811296 0.2255293 0.02772039 0.1995984 0.2451179 0.02121317 0.2008056 0.2328615 0.02121317 0.18 0.2647164 0.01148045 0.1522836 0.2484804 0 0.1604016 0.2174016 -0.01148045 0.1881179 0.2174016 -0.02121317 0.1958244 0.256282 0.01666706 0.1995984 0.2288821 0.02121317 0.1661298 0.2629492 0.005852699 0.1863999 0.2215499 0.0249601 0.150718 0.234116 -0.005852699 0.176654 0.2259703 0.02772045 0.1766995 0.2320689 0.02943718 0.1727591 0.2131299 -0.01666706 0.1928839 0.2264265 -0.02494406 0.197638 0.2252146 0.02121317 0.2008056 0.2411385 0.02121317 0.1854072 0.2641838 0.01148045 0.1805602 0.2310698 -0.02941429 0.204824 0.2345551 0.01666706 0.204925 0.238559 0.01667916 0.2077164 0.237 0.01148045 0.1550559 0.2536671 0 0.1569547 0.2216016 -0.01148045 0.1949999 0.222 0.02121317 0.1841385 0.2161944 -0.02121317 0.1910297 0.2336542 -0.02772045 0.199282 0.2528244 0.01666706 0.18 0.2202767 0.0249601 0.1714588 0.2651566 0.005852699 0.2038699 0.229759 0.01666706 0.150718 0.239884 -0.005852699 0.1726881 0.22809 0.02772039 0.1682414 0.2150013 -0.01666706 0.1917853 0.2193619 0.02121317 0.189291 0.2230951 -0.0249601 0.1812467 0.2396366 -0.02987366 0.1906065 0.2626066 0.01148045 0.1587868 0.2582132 0 0.2019987 0.2252414 0.01666706 0.1543934 0.2263934 -0.01148045 0.18 0.2157868 -0.02121317 0.1881179 0.2174016 0.02121317 0.2019987 0.2487586 0.01666706 0.1736001 0.2215498 0.0249601 0.177116 0.2662819 0.005852699 0.1820932 0.237533 -0.02993935 0.1518434 0.2455412 -0.005852699 0.199282 0.2211756 0.01666706 0.1641756 0.217718 -0.01666706 0.1692931 0.2325649 0.02773267 0.1744551 0.2355282 0.02948957 0.1841385 0.2161944 0.02121317 0.2071838 0.2315928 0.01148045 0.1953984 0.2600453 0.01148045 0.1633329 0.2619441 0 0.1528162 0.2315928 -0.01148045 0.1758615 0.2161944 -0.02121317 0.1958244 0.217718 0.01666706 0.18891 0.2296882 -0.02772039 0.2038699 0.2442409 0.01666706 0.182884 0.2662819 0.005852699 0.18 0.2157868 0.02121317 0.2056066 0.2263934 0.01148045 0.1540507 0.2508702 -0.005852699 0.160718 0.2211756 -0.01666706 0.1681748 0.2251748 0.0249601 0.1832621 0.2205979 -0.0249601 0.1917586 0.2150013 0.01666706 0.1995984 0.2565984 0.01148045 0.1685194 0.2647164 0 0.1758615 0.2161944 0.02121317 0.1522836 0.237 -0.01148045 0.2030453 0.2216016 0.01148045 0.171882 0.2174016 -0.02121317 0.1872408 0.2131299 0.01666706 0.1885412 0.2651566 0.005852699 0.2094088 0.235159 0.005860805 0.21 0.237 0 0.1685293 0.2381297 0.02772039 0.1572553 0.2556661 -0.005852699 0.1787117 0.23263 0.02965694 0.1580013 0.2252414 -0.01666706 0.171882 0.2174016 0.02121317 0.1995984 0.2174016 0.01148045 0.1796321 0.2360301 0.02999258 0.2030453 0.2523984 0.01148045 0.1741473 0.2664236 0 0.1645498 0.2306001 0.0249601 0.1528162 0.2424072 -0.01148045 0.1824449 0.212176 0.01666706 0.1769665 0.2342689 0.02972799 0.2081566 0.2284588 0.005852699 0.1682146 0.2193619 -0.02121317 0.1768013 0.2379127 0.02981603 0.1854333 0.2268348 -0.02772039 0.1938702 0.2629492 0.005852699 0.1771039 0.2396584 0.02976077 0.1750949 0.2403277 0.0294401 0.1682146 0.2193619 0.02121317 0.1953984 0.2139547 0.01148045 0.1613339 0.2597447 -0.005852699 0.1779216 0.2417603 0.02958559 0.15613 0.229759 -0.01666706 0.1783663 0.2204131 -0.02494406 0.1775551 0.212176 0.01666706 0.2056066 0.2476066 0.01148045 0.2059493 0.2231298 0.005852699 0.18 0.267 0 0.1703639 0.2434384 0.02773267 0.1543934 0.2476066 -0.01148045 0.165 0.222 0.02121317 0.165 0.222 -0.02121317 0.1906065 0.2113934 0.01148045 0.198666 0.2597447 0.005852699 0.1632767 0.237 0.0249601 0.1661298 0.2629492 -0.005852699 0.155176 0.2345551 -0.01666706 0.1727591 0.2131299 0.01666706 0.1736001 0.2215499 -0.02496016 0.2027447 0.2183338 0.005852699 0.2071838 0.2424072 0.01148045 0.1623619 0.2252146 0.02121317 0.1858527 0.2664236 0 0.1854072 0.2098162 0.01148045 0.1569547 0.2523984 -0.01148045 0.2094236 0.2311473 0 0.1623619 0.2252146 -0.02121317 0.18 0.2254109 -0.02773267 0.1682414 0.2150013 0.01666706 0.2027447 0.2556661 0.005852699 0.1714588 0.2651566 -0.005852699 0.198666 0.2142553 0.005852699 0.155176 0.2394449 -0.01666706 0.1604016 0.2288821 0.02121317 0.18 0.2092836 0.01148045 0.1914805 0.2647164 0 0.2077164 0.2255195 0 0.1604016 0.2565984 -0.01148045 0.1604016 0.2288821 -0.02121317 0.1645498 0.2433999 0.0249601 0.2059493 0.2508702 0.005852699 0.1641756 0.217718 0.01666706 0.1938702 0.2110507 0.005852699 0.177116 0.2662819 -0.005852699 0.1745666 0.2471652 0.02772039 0.15613 0.2442409 -0.01666706 0.1591944 0.2328615 0.02121317 0.1681748 0.2251748 -0.0249601 0.1787117 0.23263 -0.02965694 0.1745927 0.2098162 0.01148045 0.1766995 0.2320688 -0.02943718 0.1966671 0.2619441 0 0.2049441 0.2203329 0 0.1646016 0.2600453 -0.01148045 0.1591944 0.2328615 -0.02121317 0.160718 0.2211756 0.01666706 0.1769666 0.2342689 -0.02972799 0.2081566 0.2455412 0.005852699 0.1885412 0.2088434 0.005852699 0.182884 0.2662819 -0.005852699 0.2094088 0.235159 -0.005860805 0.2077164 0.237 -0.01148045 0.1796321 0.2360301 -0.02999258 0.1580013 0.2487586 -0.01666706 0.1587868 0.237 0.02121317 0.1693934 0.2113934 0.01148045 0.2012132 0.2582132 0 0.1693934 0.2626066 -0.01148045 0.2012132 0.2157868 0 0.1768013 0.2379127 -0.02981603 0.1744551 0.2355281 -0.02948957 0.1587868 0.237 -0.02121317 0.1774173 0.2397193 -0.02979487 0.1750949 0.2403277 -0.0294401 0.1681748 0.2488252 0.02496004 0.1745666 0.2268348 -0.02772039 0.2092819 0.239884 0.005852699 0.1580013 0.2252414 0.01666706 0.1885412 0.2651566 -0.005852699 0.182884 0.2077181 0.005852699 0.160718 0.2528244 -0.01666706 0.2081566 0.2284588 -0.005852699 0.1645498 0.2306001 -0.0249601 0.18 0.2485891 0.02773267 0.1591944 0.2411385 0.02121317 0.2049441 0.2536671 0 0.1745927 0.2641838 -0.01148045 0.1646016 0.2139547 0.01148045 0.1591944 0.2411385 -0.02121317 0.1966671 0.2120559 0 0.1938702 0.2629492 -0.005852699 0.1641756 0.256282 -0.01666706 0.15613 0.229759 0.01666706 0.177116 0.2077181 0.005852699 0.2059493 0.2231298 -0.005852699 0.2077164 0.2484804 0 0.18 0.2647164 -0.01148045 0.1604016 0.2451179 0.02121317 0.1604016 0.2451179 -0.02121317 0.1604016 0.2174016 0.01148045 0.17109 0.2296882 -0.02772039 0.1914805 0.2092836 0 0.198666 0.2597447 -0.005852699 0.1682414 0.2589987 -0.01666706 0.1736001 0.2524502 0.0249601 0.1632767 0.237 -0.02496016 0.155176 0.2345551 0.01666706 0.1714588 0.2088434 0.005852699 0.2094236 0.2428527 0 0.2027447 0.2183338 -0.005852699 0.1854072 0.2641838 -0.01148045 0.1623619 0.2487854 -0.02121317 0.1623619 0.2487854 0.02121317 0.1569547 0.2216016 0.01148045 0.2027447 0.2556661 -0.005852699 0.1727591 0.26087 -0.01666706 0.1858527 0.2075763 0 0.2071838 0.2315928 -0.01148045 0.1906065 0.2626066 -0.01148045 0.165 0.252 -0.02121317 0.155176 0.2394449 0.01666706 0.1689702 0.2336541 -0.02772045 0.1661298 0.2110507 0.005852699 0.2059493 0.2508702 -0.005852699 0.1775551 0.261824 -0.01666706 0.198666 0.2142553 -0.005852699 0.1864383 0.246636 0.02773267 0.1645498 0.2433999 -0.0249601 0.165 0.252 0.02121317 0.1953984 0.2600453 -0.01148045 0.1543934 0.2263934 0.01148045 0.1682146 0.2546381 -0.02121317 0.18 0.207 0 0.2056066 0.2263934 -0.01148045 0.2081566 0.2455412 -0.005852699 0.1824449 0.261824 -0.01666706 0.15613 0.2442409 0.01666706 0.1613339 0.2142553 0.005852699 0.1995984 0.2565984 -0.01148045 0.1938702 0.2110507 -0.005852699 0.171882 0.2565984 -0.02121317 0.1797108 0.2369984 0.0300194 0.1685293 0.2381297 -0.02772039 0.2092819 0.239884 -0.005852699 0.1682146 0.2546381 0.02121317 0.1528162 0.2315928 0.01148045 0.1872408 0.26087 -0.01666706 0.1741473 0.2075763 0 0.1681749 0.2488252 -0.0249601 0.2030453 0.2216016 -0.01148045 0.2030453 0.2523984 -0.01148045 0.1758615 0.2578056 -0.02121317 0.1917586 0.2589987 -0.01666706 0.1797108 0.2369984 -0.0300194 0.2056066 0.2476066 -0.01148045 0.18 0.2582132 -0.02121317 0.1698349 0.2424335 -0.02772039 0.1958244 0.256282 -0.01666706 0.1736001 0.2524501 -0.0249601 0.2071838 0.2424072 -0.01148045 0.1841385 0.2578056 -0.02121317 0.199282 0.2528244 -0.01666706 0.1881179 0.2565984 -0.02121317 0.1726881 0.2459099 -0.02772039 0.2019987 0.2487586 -0.01666706 0.1917853 0.2546381 -0.02121317 0.2038699 0.2442409 -0.01666706 0.204824 0.2394449 -0.01666706 + + + + + + + + + + 0.09529882 0.4790481 -0.8726001 0.2912936 0.04729592 0.955464 0.2628028 0.08059436 0.9614776 0.4966961 0.4076203 -0.7662497 0.06298053 0.6394526 0.7662466 0.1198834 0.6026278 0.7889664 -0.7860321 0.4201492 0.4534627 -0.7261836 0.4852237 0.4870477 0.1453751 0.4266426 -0.8926602 -0.7709105 -0.6326754 0.07361423 0.5108878 0.3413649 -0.7889638 -0.8252725 -0.5514466 0.1217865 0.1879543 -0.9449058 -0.2680047 0.5666794 0.3028883 -0.7662461 -0.02970206 0.301575 -0.9529798 0.2759002 -0.9095293 -0.3108629 0.277319 0.4150402 -0.8665078 0.7719248 -0.1446487 -0.6190387 0.7588584 -0.07474035 -0.6469528 0.3453172 0.2834019 0.8946728 0.6148689 0.1865342 -0.7662515 -0.2996623 0.7234486 0.6219523 -0.2219333 0.7315889 0.644611 0.6394746 0.06297695 -0.7662286 -0.9634196 0 0.2679977 -0.9458768 0.09316676 0.3108651 0.6026282 0.1198984 -0.7889637 0.03617423 0.2772665 -0.9601119 0.09688657 0.2867334 -0.9530986 -0.4701191 -0.8795285 -0.07360631 -0.3798328 -0.9170042 -0.12178 0.5654246 -0.6889668 -0.4534533 0.3453176 0.2834026 -0.8946724 0.4010347 0.2679635 -0.8759949 0.617568 -0.6175728 -0.4870458 0.1865247 0.6148769 0.7662474 0.1627876 0.2246037 -0.9607567 -0.6889615 0.5654243 0.4534617 0.4639387 0.07768434 -0.8824546 0.4730575 0.09409534 -0.8759925 -0.6175706 0.6175689 0.4870474 -0.9170053 -0.3798286 0.1217857 0.2404469 0.1973381 -0.950391 -0.8795281 -0.4701204 0.07360219 0 -0.963419 -0.2679999 0.09316635 -0.945877 -0.3108645 0.2557009 0.09336608 -0.9622369 0.7315902 -0.2219374 -0.644608 0.7234456 -0.2996645 -0.6219547 0.2943527 0.04783409 -0.954499 0.09115821 0.3144091 0.9449006 0.4010343 0.2679651 0.8759944 0.1397676 -0.04219394 0.9892849 -0.07493537 0.7608307 0.6446095 -0.1527693 0.7680097 0.6219506 -0.9095311 0.2758974 0.31086 -0.9449061 0.1879571 0.2680012 -0.6326719 -0.7709137 -0.07360941 0.1152628 -0.06091368 0.9914657 -0.5514428 -0.8252751 -0.1217862 0.4852241 -0.7261823 -0.4870492 0.4201482 -0.7860347 -0.4534589 0.3028942 0.5666736 0.7662481 0.34136 0.5108871 0.7889663 -0.4852238 0.7261855 0.4870448 -0.5654253 0.688967 0.4534522 -0.9543435 -0.2894992 0.07361268 -0.9734845 -0.1936378 0.1217882 -0.187953 -0.9449064 -0.2680029 -0.09316724 -0.9458785 -0.31086 0.6742447 -0.3603827 -0.6446073 0.6510839 -0.4350449 -0.6219531 0 0.7830505 0.6219582 0.07493579 0.7608353 0.644604 -0.8900867 0.3686751 0.2680007 -0.83822 0.4480497 0.3108677 -0.7709106 -0.6326755 -0.07361257 -0.7018464 -0.7018395 -0.1217908 0.3342274 -0.806894 -0.4870464 0.07508593 -0.1531382 0.9853481 0.258722 -0.8528969 -0.4534645 0.6394714 -0.06297653 -0.7662312 0.4076254 0.4967012 0.7662438 -0.3342306 0.8068957 0.4870415 -0.4201473 0.7860293 0.453469 -0.9925571 0 0.1217803 -0.992486 -0.09774386 0.07360661 -0.2759003 -0.9095297 -0.3108612 -0.3686784 -0.8900848 -0.2680029 0.2914202 -0.03809583 0.9558363 0.2644917 -0.08214211 0.9608834 0.5909837 -0.4850004 -0.6446029 0.5537025 -0.5537031 -0.6219538 0.4730588 0.09409826 0.8759915 0.4639419 0.07768481 0.8824529 0.2219325 0.7315911 0.6446088 0.1527693 0.7680097 0.6219506 -0.7347092 0.6029698 0.3108534 -0.801048 0.5352529 0.2680047 -0.879528 -0.4701204 -0.07360303 -0.8252727 -0.5514467 -0.1217848 0.2669201 -0.1426691 0.9530998 0.08736646 -0.886987 -0.4534549 0.1703892 -0.8565939 -0.4870465 0.4644643 -0.06150215 0.8834537 0.6148719 -0.1865347 -0.766249 0.6026257 -0.1198971 -0.7889658 0.5108873 0.3413643 0.7889644 0.07428574 0.1513321 0.9856877 0.4966976 0.4076239 0.7662469 -0.1703913 0.8565924 0.4870485 -0.2587213 0.8529016 0.4534558 -0.9734843 0.1936377 0.1217899 -0.992486 0.09774386 0.07360643 0.4790571 -0.09528809 0.8725965 0.1920114 -0.2339583 0.9530977 -0.5352566 -0.8010477 -0.2679983 -0.4480445 -0.8382226 -0.3108683 0.4350435 -0.6510828 -0.6219552 0.1017582 0.0719195 0.9922061 0.4849995 -0.5909849 -0.6446025 0.2996646 0.7234418 0.6219591 0.3603894 0.6742444 0.6446039 0.4050892 -0.216513 0.8882707 -0.6812402 0.6812404 0.267999 0.09254026 -0.2687934 0.9587422 0.1403958 0.04096275 0.9892477 -0.6029672 0.734709 0.3108592 0.08698183 0.2903618 -0.9529556 0.1222395 -0.2448533 0.9618235 -0.9543435 -0.2894992 -0.07361268 -0.9170054 -0.3798287 -0.121784 0.1384826 -0.04264444 -0.9894464 0 -0.8733733 -0.4870515 -0.08736586 -0.8869848 -0.4534592 0.4061192 -0.2713603 0.8726001 0.1144276 -0.06068164 -0.9915766 0.5666753 -0.3028903 -0.7662484 0.08598339 -0.2834571 0.9551225 0.5666801 0.302889 0.7662454 0.6394688 -0.06297647 0.7662334 0.6026296 -0.119898 0.7889628 -0.08736616 0.8869892 0.4534505 0 0.8733767 0.4870454 -0.9170048 0.3798295 0.1217859 -0.9543434 0.2894999 0.07361114 -0.6812396 -0.6812397 -0.2680022 0.2913951 -0.3550524 0.8882719 -0.6029682 -0.7347069 -0.3108619 0.2996621 -0.7234414 -0.6219608 0.3603879 -0.6742426 -0.6446066 0.4350408 0.6510826 0.6219574 0.6148647 -0.1865327 0.7662551 0.4849998 0.5909848 0.6446024 -0.4480476 0.8382283 0.3108487 -0.5352457 0.8010574 0.2679912 0.2713608 -0.4061182 0.8726004 -0.992486 -0.09774386 -0.07360643 -0.9734845 -0.1936378 -0.1217882 -0.06354516 -0.2699825 0.9607662 -0.1703909 -0.8565908 -0.4870516 -0.02902317 -0.294655 0.955163 -0.2587203 -0.8528989 -0.4534617 0.4970431 -0.4079043 -0.7658735 0.5108876 -0.3413618 0.7889651 0.5666799 -0.3028891 0.7662455 0.5297594 -0.3287399 -0.7818472 0.6148687 0.1865342 0.7662516 0.6394784 0.06297743 0.7662254 0.602626 0.119899 0.7889653 0.08736616 0.8869855 0.4534578 0.1703895 0.8565956 0.4870435 0.13333 -0.4395483 0.8882682 0.07310873 -0.153744 -0.9854025 0.7608317 -0.07493394 0.6446085 0.7772105 -0.02149385 0.6288735 0.8778201 -0.02358704 0.4784094 -0.8795282 0.4701205 0.07360136 -0.8252736 0.5514457 0.1217828 -0.8010472 -0.5352539 -0.2680053 -0.7347075 -0.6029685 -0.3108599 0.2219352 -0.7315906 -0.6446084 0.4967029 -0.4076284 0.766241 0.1527695 -0.7680118 -0.6219482 0.46447 -0.06149989 -0.8834509 0.4790547 -0.09528917 -0.8725976 0.5537047 0.5537026 0.6219522 0.5909828 0.4849997 0.6446043 0.0952996 -0.4790454 0.8726016 -0.3686916 0.8900807 0.2679982 -0.2759 0.9095287 0.3108645 0.7680126 -0.1527729 0.6219462 0.7315902 -0.2219374 0.644608 -0.992486 0.09774386 -0.07360643 -0.9925571 0 -0.1217803 -0.1428247 -0.2672073 0.952996 -0.4201495 -0.7860334 -0.4534602 -0.3342276 -0.8068948 -0.4870449 0.3413617 -0.510888 0.7889649 0.4076216 -0.4966973 0.7662483 0.4076232 -0.4966992 -0.7662461 0.4257774 -0.455445 -0.7818462 0.2587229 0.8528996 0.4534586 0.3342306 0.8068957 0.4870415 -0.04502898 -0.4571062 0.8882716 0.02239066 0.1512652 -0.9882397 -0.7709106 0.6326755 0.07361257 -0.7018457 0.701839 0.1217976 0.6742436 -0.3603821 0.6446086 -0.8900864 -0.368674 -0.2680034 0.7234445 -0.2996641 0.6219561 -0.83822 -0.4480497 -0.3108677 0 -0.7830565 -0.6219506 0.07493525 -0.760833 -0.6446068 0.3028934 -0.5666754 0.766247 0.09095108 0.1260352 -0.9878477 0.6510823 0.4350438 0.6219557 0.6742478 0.3603844 0.6446031 -0.09529823 -0.4790491 0.8725997 -0.1879559 0.9449087 0.2679932 -0.09316688 0.9458752 0.3108699 0.1082704 0.07451027 -0.9913253 -0.9734843 0.1936377 -0.1217901 -0.9543434 0.2894999 -0.07361114 0.5909826 -0.4849998 0.6446044 0.651084 -0.4350448 0.6219531 -0.4852238 -0.7261817 -0.4870503 -0.565426 -0.6889649 -0.4534544 0.1383476 0.05066323 -0.9890871 -0.231684 -0.1648313 0.9587247 -0.232021 -0.1786494 0.9561646 0.3028942 -0.5666722 -0.7662491 0.09488826 -0.2797646 -0.9553681 0.1865262 -0.614875 0.7662486 0.119883 -0.6026197 0.7889725 0.8869837 -0.08737099 0.4534603 0.8565931 -0.1703931 0.4870468 0.4852238 0.7261855 0.4870448 0.4201464 0.7860314 0.4534662 -0.5514296 0.8252822 0.1217975 -0.6326721 0.770914 0.07360601 -0.9449058 -0.1879569 -0.2680028 -0.9095311 -0.2758975 -0.31086 -0.2165211 -0.4050887 0.888269 -0.1527695 -0.7680118 -0.6219482 0.5537027 -0.553703 0.6219537 0.4849998 -0.5909848 0.6446024 -0.07493525 -0.760833 -0.6446068 0.405922 -0.2529682 -0.8781996 0.4050876 -0.2165151 -0.888271 0.7234408 0.2996627 0.6219612 0.7315972 0.2219393 0.6445995 0 0.963419 0.2679999 0.06298017 -0.639455 0.7662448 0.09316647 0.9458781 0.3108612 0.8529007 -0.2587195 0.4534586 -0.917005 0.3798295 -0.1217847 0.806892 -0.334221 0.4870539 -0.8795282 0.4701205 -0.07359963 -0.6889649 -0.5654272 -0.453453 -0.2713599 -0.4061151 0.8726021 -0.6175691 -0.6175699 -0.4870482 0.2351261 -0.5676671 -0.7889676 0.1865257 -0.614872 -0.766251 0.4350435 -0.6510828 0.6219552 0.2933167 -0.03835421 -0.9552457 0.3603881 -0.6742424 0.6446067 0.5654236 0.6889687 0.4534518 0.6175692 0.6175714 0.4870461 -0.4701189 0.8795282 0.07360965 -0.06297975 -0.6394554 0.7662443 -0.1198813 -0.6026214 0.7889714 -0.3798452 0.916997 0.1217962 -0.9458765 -0.09316676 -0.3108659 0.7860322 -0.4201529 0.453459 -0.9634196 0 -0.2679977 0.726185 -0.4852246 0.4870446 -0.2219359 -0.7315884 -0.6446106 -0.3637939 -0.2784389 0.8888903 -0.2996595 -0.7234473 -0.6219553 0.3272963 -0.348761 -0.8782044 0.7588654 0.07473683 0.6469449 0.771921 0.1446427 0.6190448 0.2996621 -0.7234414 0.6219608 0.2219352 -0.7315906 0.6446084 0.1879571 0.9449079 0.2679949 0.2759 0.9095287 0.3108645 0.944541 -0.09303575 0.3149393 -0.8252739 0.5514459 -0.1217812 0.01347672 -0.1363958 0.9905629 -0.7709106 0.6326755 -0.07361257 -0.04823946 -0.2094644 0.9766257 -0.301663 -0.03930532 0.9526041 -0.7261835 -0.4852237 -0.4870477 -0.1865273 -0.6148689 0.7662531 -0.7860348 -0.4201504 -0.4534567 0.06298029 -0.6394493 -0.7662494 0.6889693 -0.5654196 0.4534557 0.6175676 -0.6175724 0.4870469 0.2641661 -0.08455508 -0.9607636 0.7261836 0.4852237 0.4870477 0.6889665 0.5654172 0.453463 -0.193641 0.973482 0.1218033 -0.2895037 0.9543429 0.07360219 -0.4010373 -0.2679614 0.8759942 -0.9449058 0.1879569 -0.2680028 0.1527695 -0.7680118 0.6219482 0.07493555 -0.760833 0.6446068 -0.9458771 0.09316682 -0.3108642 -0.07411921 -0.1218199 0.989781 0.9095302 -0.2759007 0.3108597 -0.04126691 -0.08707535 0.9953467 0.9483677 -0.1775622 0.2628129 -0.4350435 -0.6510828 -0.6219552 -0.3603891 -0.6742398 -0.6446087 -0.267367 0.04555761 0.9625173 0.2913943 -0.3550524 -0.8882721 0.4480462 0.8382294 0.3108477 -0.3028923 -0.5666788 0.7662451 0.3686927 0.8900799 0.267999 -0.3413614 -0.5108892 0.7889643 0.4852238 -0.7261818 0.4870504 0.5654246 -0.6889668 0.4534533 -0.7018459 0.7018391 -0.1217959 -0.6326721 0.770914 -0.07360601 -0.1149753 0.1268253 0.985239 -0.8068891 -0.3342278 -0.4870541 -0.8529008 -0.2587195 -0.4534586 0.02097147 -0.6231193 -0.7818457 0.002302825 0.1379625 0.9904348 -0.0630235 -0.6398969 -0.7658721 -0.07493555 -0.760833 0.6446068 0.2665275 -0.1424605 -0.9532409 0 -0.7830585 0.6219481 0.8068944 0.334222 0.4870493 0.8382241 -0.4480411 0.3108692 0.7860316 0.4201525 0.4534605 0.8900852 -0.3686769 0.2680031 0 0.9925558 0.1217907 -0.09774023 0.9924868 0.07359945 -0.2819479 0.09523189 0.9546918 -0.9095308 0.2758974 -0.3108608 -0.8900867 0.3686751 -0.2680007 -0.4076209 -0.4966989 0.7662476 -0.4849998 -0.5909848 -0.6446024 -0.5537013 -0.5537059 -0.6219524 0.334227 -0.8068932 0.487048 0.4201481 -0.7860347 0.4534589 0.1869121 -0.4512628 -0.8725971 0.6029656 0.7347106 0.3108583 0.5352472 0.8010562 0.2679919 -0.4730548 -0.09410512 0.8759929 -0.4701188 0.879528 -0.07361298 -0.4541268 -0.0603699 0.8888894 -0.5514296 0.8252823 -0.1217975 -0.8565948 -0.1703853 -0.4870467 -0.1527693 -0.7680118 0.6219482 -0.8869837 -0.08737099 -0.4534603 -0.2219359 -0.7315884 0.6446106 -0.1421498 -0.6070422 -0.7818526 0.8010427 -0.5352613 0.2680038 0.7347108 -0.6029639 0.3108613 -0.1865267 -0.6148725 -0.7662504 0.8528987 0.2587188 0.453463 0.8883474 0.08750826 0.4507563 0.856527 0.16008 0.4906486 -0.496698 -0.4076218 0.7662478 0.09774088 0.9924865 0.07360333 -0.5108903 -0.341361 0.7889638 0.258722 -0.8528969 0.4534645 0.1936398 0.9734824 0.1218025 -0.801048 0.5352529 -0.2680048 0.1703895 -0.8565956 0.4870435 -0.83822 0.4480497 -0.3108681 0.9927842 -0.09777259 0.06942766 0.9749566 -0.1823666 0.1272876 -0.6510862 -0.4350383 -0.6219554 -0.5909839 -0.4849962 -0.6446058 0.1161469 -0.4355061 -0.8926614 -0.2996593 -0.7234473 0.6219553 0.6812385 0.6812422 0.2679983 0.7347124 0.6029652 0.3108547 -0.3603891 -0.6742398 0.6446087 -0.3798453 0.9169973 -0.1217928 0.6812379 -0.6812416 0.2680015 -0.2895038 0.9543432 -0.07359886 -0.8733747 0 -0.4870491 0.6029666 -0.7347087 0.3108611 -0.8869841 0.08737105 -0.4534598 -0.3028939 -0.5666754 -0.766247 -0.5666747 -0.3028896 0.7662491 0.08736652 -0.8869869 0.4534548 0 -0.8733733 0.4870515 0.1921276 -0.2341007 -0.9530393 0.2895075 0.9543418 0.07360315 0.9170064 -0.3798257 0.1217858 0.9543435 -0.2894992 0.07361268 0.3798404 0.9169992 0.1217947 -0.7347094 0.6029701 -0.3108526 -0.6812402 0.6812403 -0.2679989 -0.674239 -0.360394 -0.6446068 -0.4790505 0.09530031 0.8725988 -0.7234465 -0.2996608 -0.6219555 0.01569503 -0.4910939 -0.8709653 -0.4266399 0.1453769 0.8926612 0.8382241 0.4480411 0.3108692 -0.4350434 -0.6510827 0.6219555 0.8010434 0.5352602 0.2680041 -0.4849998 -0.5909848 0.6446024 0.5352575 -0.8010457 0.2680022 -0.193641 0.973482 -0.1218033 0.4480432 -0.8382236 0.3108673 -0.09774023 0.9924868 -0.07359945 -0.1966002 0.2248459 0.9543546 -0.8565948 0.1703853 -0.4870466 -0.1651983 0.2285466 0.9594144 -0.8528987 0.2587188 -0.453463 -0.6026242 -0.119879 0.7889698 -0.4076207 -0.4966965 -0.7662494 -0.3413597 -0.5108874 -0.7889662 -0.6148711 -0.1865292 0.7662509 0.01409959 -0.1373293 -0.9904251 -0.08736592 -0.8869848 0.4534592 -0.1703913 -0.8565924 0.4870485 -0.0483334 -0.2091578 -0.9766867 0.4701176 0.8795289 0.07360941 0.879528 -0.4701204 0.07360303 0.5514327 0.8252801 0.1217982 0.8252725 -0.5514466 0.1217865 -0.6029665 0.7347081 -0.3108624 -0.5352462 0.8010582 -0.267988 -0.7680137 -0.1527689 -0.6219459 -0.7315904 -0.2219373 -0.6446079 -0.1062127 -0.4577892 -0.8826936 -0.5909839 -0.4849962 0.6446058 -0.5537016 -0.5537058 0.6219522 0.9095302 0.2759007 0.3108597 0.2759 -0.9095287 0.3108645 0.8900857 0.3686782 0.268 -0.07411587 -0.1218183 -0.9897814 0.3686795 -0.890084 0.2680037 0 0.9925562 -0.1217873 0.09774088 0.9924867 -0.07359993 0.9927842 -0.09777259 -0.06942766 -0.7860333 0.4201499 -0.4534598 -0.8068922 0.3342291 -0.487048 -0.04126483 -0.08707755 -0.9953466 -0.4966998 -0.4076233 -0.7662458 -0.6394503 -0.0629791 0.7662486 0.1208289 -0.2456647 -0.9617948 0.07844138 -0.2911047 -0.95347 -0.334227 -0.8068932 0.487048 -0.2587204 -0.8528988 0.4534616 0.7018407 0.7018442 0.1217967 0.6326737 0.7709127 0.07360625 -0.4480476 0.8382283 -0.3108487 -0.3686913 0.8900798 -0.2680014 0.7018413 -0.7018448 0.12179 0.7709137 -0.6326713 0.07361453 -0.7830559 0 -0.6219514 -0.760831 -0.07492923 -0.6446099 -0.4150454 0.2773233 0.8665041 -0.1180158 -0.4426696 -0.8888847 0.9595323 0.02625322 0.2803724 0.9937137 0.02688425 0.1086761 -0.6742402 -0.3603945 0.6446053 0.9449059 0.187957 0.268002 0.9458765 0.09317034 0.3108649 0.2895075 0.954342 -0.07359981 -0.1074534 0.1618098 -0.9809544 -0.6510854 -0.4350377 0.6219567 0.1936398 0.9734824 -0.1218025 0.09316623 -0.9458761 0.3108677 -0.7261829 0.4852231 -0.4870491 0.1879544 -0.9449066 0.2680014 -0.01779818 0.1214079 -0.9924432 -0.6889616 0.5654243 -0.4534617 0.9543435 -0.2894992 -0.07361268 -0.5666736 -0.3028891 -0.7662502 0.9749565 -0.1823675 -0.1272877 -0.5108896 -0.3413616 -0.7889639 -0.05962419 0.278272 0.95865 -0.07623165 0.2826546 0.9561879 -0.6026242 0.1198766 0.7889702 0.770914 0.6326715 0.07361119 -0.6394526 0.06297934 0.7662467 0.8252736 0.5514457 0.1217828 -0.2759 0.9095287 -0.3108645 -0.4201497 -0.786034 0.4534587 -0.1879557 0.9449078 -0.2679963 -0.4852238 -0.7261818 0.4870504 -0.7608357 0.07492965 -0.6446043 0.5514461 -0.8252733 0.1217835 0.6326735 -0.7709124 0.07360959 -0.7680091 0.1527681 -0.6219518 -0.2713597 -0.4061186 -0.8726006 -0.2975814 0.3385249 0.8926625 0.4701175 0.8795288 -0.0736128 0.3798406 0.9169996 -0.1217913 -0.5654253 0.688967 -0.4534521 -0.6175701 0.6175683 -0.4870489 -0.7234473 -0.2996612 0.6219544 -0.7315902 -0.2219374 0.644608 0 -0.963419 0.2679999 -0.0931673 -0.9458795 0.3108568 -0.6148709 -0.1865292 -0.766251 0.9170066 -0.3798258 -0.1217842 0.879528 -0.4701204 -0.07360303 0.917006 0.3798266 0.1217861 0.8795282 0.4701205 0.07360136 0 0.963419 -0.2679999 -0.09316676 0.9458742 -0.3108732 -0.6148709 0.1865292 0.766251 0.02921271 -0.03009545 0.9991201 0.0307675 -0.03756517 0.9988204 -0.7315972 0.2219393 -0.6445995 -0.5654257 -0.6889644 0.4534555 -0.7234426 0.2996594 -0.6219608 -0.6175692 -0.6175699 0.4870482 -0.01459592 -0.09430837 0.9954361 0.3798278 -0.917006 0.1217819 -0.2913942 -0.3550507 -0.8882728 0.4701176 -0.8795291 0.07360607 0.5514327 0.8252801 -0.1217982 0.6326737 0.7709127 -0.07360625 -0.149282 -0.1117283 0.9824621 -0.4852231 0.7261844 -0.4870471 -0.4201481 0.7860308 -0.4534661 -0.6394501 -0.06297898 -0.7662488 -0.2713593 0.4061198 0.8726 -0.6026248 -0.1198804 -0.788969 -0.7608319 -0.07492929 0.6446087 -0.1393058 0.05545622 0.9886954 -0.07621371 -0.2825845 -0.95621 -0.1704301 0.03286409 0.9848217 -0.06630742 -0.2781938 -0.9582337 -0.7680131 -0.1527689 0.6219466 -0.2759 -0.9095287 0.3108645 0.9924865 0.09773719 0.07360649 0.9543434 0.2894999 0.07361072 0.9734823 0.1936476 0.1217896 -0.1879532 -0.9449074 0.2679997 0.8252727 -0.5514467 -0.1217857 0.187957 0.9449071 -0.2679981 -0.05671751 0.04141873 0.9975308 0.7709139 -0.6326714 -0.07361286 0.09316635 0.945877 -0.3108645 -0.6742433 0.3603961 -0.6446012 -0.6510846 0.4350371 -0.6219579 -0.4061206 -0.271359 -0.8725998 -0.01012617 0.08694875 0.9961614 -0.5666714 0.3028929 0.7662504 -0.5108884 0.3413625 0.7889643 -0.726185 -0.4852246 0.4870446 0.7709139 0.6326714 -0.07361286 -0.03730237 0.0767551 0.996352 0.7018411 0.7018445 -0.1217933 -0.6889644 -0.5654268 0.453454 -0.2587213 0.8529016 -0.4534558 0.1936376 -0.9734845 0.121789 -0.3342303 0.8068949 -0.487043 -0.6394533 0.06297934 -0.7662462 0.2895048 -0.9543415 0.07361662 0.9483675 -0.1775623 -0.2628129 0.944541 -0.09303575 -0.3149392 0.03076678 -0.03756386 -0.9988205 0.2759 0.9095287 -0.3108645 -0.1180164 0.442669 0.888885 0.3686924 0.8900791 -0.2680022 0.02921193 -0.03009545 -0.9991201 -0.5537031 0.5537051 -0.6219515 -0.7608354 0.07492965 0.6446046 -0.5909842 0.4849961 -0.6446058 -0.7830559 0 0.6219514 -0.01459687 -0.09430652 -0.9954363 -0.4480445 -0.8382226 0.3108683 -0.4050893 -0.2165167 -0.8882697 0.8252736 0.5514457 -0.1217828 -0.1492792 -0.1117277 -0.9824627 -0.3686786 -0.8900851 0.2680012 0.8795282 0.4701205 -0.07359963 -0.1703913 0.8565924 -0.4870485 -0.1359078 0.05791264 -0.9890275 0.6326735 -0.7709124 -0.07360959 -0.08736592 0.8869878 -0.4534534 -0.1704276 0.03286415 -0.984822 0.7018413 -0.7018448 -0.12179 0.08865237 0.2922561 0.9522222 0.1227717 0.2433772 0.9621303 -0.6026227 0.1198801 -0.7889706 -0.6148713 0.1865292 -0.7662507 -0.1922453 -0.2342443 -0.9529802 -0.05968451 0.03202456 -0.9977036 -0.4966968 0.4076221 0.7662484 0.5352476 0.8010569 -0.2679887 -0.80689 -0.3342282 0.4870526 0.4480462 0.8382294 -0.3108477 -0.7860341 -0.4201502 0.4534583 -0.4849992 0.5909844 -0.6446032 -0.4350404 0.6510819 -0.6219585 0.09774333 -0.992486 0.07360666 0 -0.9925558 0.1217907 -0.4790517 -0.09529948 -0.8725982 0.8900853 -0.368677 -0.2680031 0.9095302 -0.2759008 -0.3108597 0.9170062 0.3798267 -0.1217845 0.9543434 0.2894999 -0.07361114 0.08736592 0.8869841 -0.4534607 -0.09410506 0.4730499 0.8759955 0 0.8733767 -0.4870454 -0.01909703 0.06622678 -0.9976218 -0.7680091 0.1527681 0.6219518 -0.7315972 0.2219393 0.6445995 -0.5666736 0.3028891 -0.7662502 -0.6029682 -0.7347069 0.3108619 -0.5352563 -0.8010474 0.2679999 0.6029649 0.7347098 -0.3108616 0.6812386 0.6812421 -0.2679983 0.4701176 -0.8795291 -0.07360607 0.551446 -0.825273 -0.1217868 -0.36039 0.6742408 -0.6446071 -0.2996623 0.7234486 -0.6219523 -0.08519148 -0.02071845 0.9961493 -0.09822469 -0.0075019 0.995136 -0.4571037 -0.04502183 -0.8882732 0.9924865 0.09773719 -0.07360649 0.9937137 0.02688425 -0.1086761 0.9595323 0.02625322 -0.2803724 -0.4076226 0.496697 0.7662479 -0.08582431 -0.0517708 0.9949644 0.9734823 0.1936476 -0.1217896 -0.3413631 0.5108894 0.7889633 -0.8529006 -0.2587195 0.4534586 0.1703895 0.8565956 -0.4870435 -0.8565942 -0.1703853 0.4870474 0.2587229 0.8528996 -0.4534586 -0.09774273 -0.9924864 0.07360279 -0.5108866 0.3413619 -0.7889658 -0.4966979 0.4076256 -0.7662458 -0.1936389 -0.973484 0.1217899 0.02437561 0.0409891 0.9988622 0.8010427 -0.5352613 -0.2680038 -0.2605676 -0.1392736 -0.9553572 -0.2257234 -0.1609959 -0.9607962 0.8382243 -0.4480412 -0.3108684 0.7347124 0.6029652 -0.3108547 0.8010435 0.5352603 -0.2680032 -0.2219334 0.73159 -0.6446096 -0.1527698 0.7680116 -0.6219481 -0.4790476 0.09529691 -0.8726007 -0.7234417 0.2996589 0.621962 -0.6742443 0.3603966 0.6445998 0.4201468 0.7860321 -0.4534648 -0.7347075 -0.6029685 0.3108599 0.3342306 0.8068957 -0.4870415 -0.4076227 0.4966982 -0.7662472 -0.6812397 -0.6812399 0.2680014 -0.08519148 -0.02071547 -0.9961493 -0.09822648 -0.007504105 -0.9951359 0.379828 -0.9170064 -0.1217785 0.2895049 -0.9543418 -0.07361328 -0.08582216 -0.05176872 -0.9949647 0.8883501 -0.08750158 -0.4507524 0.8382241 0.448041 -0.3108692 0.8900856 0.3686781 -0.2680004 0 0.7830525 -0.6219557 -0.07493561 0.7608307 -0.6446095 -0.3028912 0.5666759 0.7662476 0.02437829 0.0409891 -0.9988622 -0.8733747 0 0.4870491 -0.4395411 0.1333308 -0.8882718 -0.8869837 -0.08737099 0.4534603 0.4852228 0.726184 -0.4870479 -0.3798326 -0.9170038 0.1217834 0.5654239 0.688969 -0.453451 -0.2895011 -0.9543427 0.07361567 -0.3028911 0.5666682 -0.7662534 0.681238 -0.6812416 -0.2680016 -0.3413563 0.5108916 -0.7889651 -0.297755 -0.02932763 -0.9541918 0.7347106 -0.6029638 -0.3108617 0.9095302 0.2759008 -0.3108597 0.9458768 0.0931704 -0.3108641 0.9449058 0.1879569 -0.2680028 0.1527698 0.7680116 -0.6219481 0.07493585 0.7608331 -0.6446067 0.1296769 0.4274993 0.8946666 0.09410679 0.4730447 0.8759981 -0.5909842 0.4849961 0.6446058 -0.4061235 0.2713651 -0.8725965 -0.6510863 0.4350382 0.6219553 0.6175692 0.6175714 -0.4870462 -0.83822 -0.4480497 0.3108677 -0.8010472 -0.535254 0.2680049 0.6889659 0.5654168 -0.4534645 -0.1865252 0.6148721 -0.766251 0.1936376 -0.9734845 -0.121789 0.09774333 -0.992486 -0.07360666 0.8529008 -0.2587195 -0.4534586 0.8565255 -0.1600863 -0.4906489 0.2219326 0.7315911 -0.6446087 0.299665 0.7234427 -0.6219578 0.245914 0.2018232 0.9480474 -0.3550513 0.2913983 -0.8882712 -0.1198795 0.6026234 0.7889703 -0.1865256 0.6148751 0.7662487 0.7261822 0.4852227 -0.4870507 -0.8869837 0.08737099 0.4534604 0.7860321 0.420153 -0.4534592 -0.06298005 0.6394554 -0.7662443 -0.1198832 0.6026263 -0.7889675 -0.8565948 0.1703853 0.4870467 -0.4701191 -0.8795285 0.07360631 -0.2673687 0.04555761 -0.9625167 -0.551443 -0.8252755 0.1217828 -0.2788856 0.08459961 -0.9565908 0.6029663 -0.7347085 -0.310862 0.3603894 0.6742444 -0.6446039 0.5352581 -0.8010465 -0.2679991 0.4350404 0.6510819 -0.6219585 -0.2713583 0.4061208 -0.8725998 0.8528987 0.2587188 -0.453463 0.8068944 0.334222 -0.4870494 -0.5537031 0.553705 0.6219514 0.06298047 0.6394498 -0.766249 -0.4849998 0.5909848 0.6446024 -0.8900862 -0.3686739 0.2680042 -0.9095311 -0.2758974 0.31086 0 -0.9925562 -0.1217873 0.5537043 0.5537022 -0.6219529 0.4849983 0.590983 -0.6446052 -0.09774267 -0.9924861 -0.07360619 -0.2165226 0.4050914 -0.8882675 0.7860336 -0.4201534 -0.4534561 0.806892 -0.334221 -0.4870539 0.8869841 0.08737105 -0.4534598 0.8778204 0.02358675 -0.4784089 0.8565935 0.1703931 -0.4870459 0.7772111 0.02150344 -0.6288725 0.1198822 0.6026272 -0.7889669 0.1865246 0.6148751 -0.7662488 -0.06298053 0.6394526 0.7662466 -0.2344939 0.1924518 -0.9528772 -0.8528993 0.258719 0.4534615 0.5909827 0.4849998 -0.6446043 -0.8068922 0.3342291 0.487048 0.6510823 0.4350438 -0.6219557 -0.6326719 -0.7709137 0.07360941 -0.09529936 0.4790484 -0.8726 -0.7018463 -0.7018396 0.1217908 0.4480429 -0.8382232 -0.3108689 0.3028934 0.5666723 -0.7662494 0.3686795 -0.890084 -0.2680037 0.2773206 0.4150434 0.8665058 0.7234416 0.2996631 -0.62196 -0.4350404 0.6510819 0.6219585 0.6742466 0.3603838 -0.6446045 -0.04502433 0.4571074 -0.8882712 -0.3603905 0.6742418 0.6446059 -0.9449056 -0.1879569 0.2680028 -0.9458765 -0.09316676 0.3108659 0.4076247 0.4967021 -0.7662436 0.3413627 0.5108919 -0.788962 -0.2895011 -0.9543429 -0.07361233 -0.1375851 0.2574023 -0.9564594 -0.1936389 -0.973484 -0.1217899 -0.1525414 0.2303131 -0.9610865 0.7680086 0.1527721 -0.6219514 0.7608354 0.07493436 -0.644604 0.7261843 -0.4852241 -0.4870462 0.7315949 0.2219386 -0.6446024 0.6889692 -0.5654197 -0.4534558 + + + + + + + + + + + + + + +

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

+
+
+
+ + + + -0.02298343 0.1895948 0.1505221 -0.00560534 0.1942121 0.1386047 -0.007439672 0.1989769 0.1377117 -0.02175551 0.184562 0.1503556 -0.004383623 0.1891778 0.1384426 -0.02126252 0.1795384 0.1491789 -0.003845453 0.1841661 0.1372349 -0.02153313 0.1748158 0.14706 -0.004022121 0.1794688 0.1350516 -0.04754084 0.1899016 0.116759 -0.02844661 0.1949751 0.1036648 -0.0279085 0.1899635 0.102457 -0.04704779 0.1848781 0.1155822 -0.02255159 0.1706691 0.1441223 -0.004903435 0.1753582 0.1320198 -0.04727023 0.1946241 0.1188778 -0.02826994 0.1996726 0.105848 -0.02425873 0.1673388 0.1405363 9.99804e-4 0.1741008 0.1236042 -0.04625177 0.1987709 0.1218156 -0.02738863 0.203783 0.1088799 -0.02655535 0.1650187 0.1365106 -8.36576e-4 0.1718522 0.119224 -0.04454457 0.2021012 0.1254016 -0.01814979 0.209167 0.1077042 -0.02930802 0.1638435 0.132279 0.01210004 0.1747782 0.1051594 -0.04224795 0.2044214 0.1294274 -0.01589947 0.2114223 0.1117159 -0.03246545 0.1638522 0.1279202 -0.03949534 0.2055965 0.133659 0.002060949 0.2165703 0.1064432 -0.03552412 0.1651307 0.1241797 -0.01687902 0.1700848 0.1113934 -0.03655326 0.2055296 0.1376865 -0.03862643 0.1675184 0.1207827 -0.01980173 0.1725202 0.1078733 -0.04148316 0.1709057 0.1180939 -0.02251207 0.1759465 0.1050841 -0.03327918 0.2043093 0.1417582 -0.01541304 0.2090564 0.1295062 -0.04392832 0.1750957 0.1162696 -0.02485239 0.1801645 0.1031879 -0.04581987 0.1798453 0.1154159 -0.02668672 0.1849291 0.1022949 -0.03017693 0.2019217 0.1451552 -0.01249033 0.2066211 0.1330263 -0.0273202 0.1985344 0.147844 -0.009780049 0.2031949 0.1358155 -0.02487498 0.1943442 0.1496683 0.01254665 0.1989578 0.1273157 0.0107581 0.2037345 0.1263942 0.01375961 0.1939211 0.1271591 0.01432651 0.188917 0.1259334 0.01421439 0.1842364 0.12371 -0.009040772 0.2000485 0.091596 -0.008473873 0.1950443 0.09037035 0.01342982 0.1801513 0.120618 -0.008928656 0.2047291 0.09381943 -0.00814408 0.2088142 0.09691143 0.01268261 0.1757527 0.09894824 0.01147538 0.177536 0.09383481 0.007916271 0.217251 0.1091552 -6.1177e-4 0.1775372 0.0959388 -0.003212213 0.1809921 0.09308129 0.01222443 0.2163195 0.1123917 -0.005472362 0.1852311 0.0911352 -0.007260918 0.1900077 0.09021371 0.01586616 0.2141168 0.1154727 0.008497893 0.2079734 0.1244482 0.03710752 0.1999679 0.1137486 0.03572231 0.2049589 0.1139905 0.03787928 0.1950135 0.1124196 0.01637506 0.2065561 0.07699787 0.015271 0.2011246 0.07672297 0.03801846 0.1903907 0.1100644 0.04000413 0.1869788 0.1053861 0.01590389 0.2111487 0.07958269 0.04024338 0.1841484 0.1006805 0.01934754 0.2158774 0.08115231 0.03542709 0.181195 0.09807264 0.02219969 0.2194976 0.08412957 0.02098721 0.2209256 0.09019917 0.02254867 0.1835138 0.08259356 0.02047836 0.1871133 0.07943814 0.01857411 0.1914517 0.07729631 0.01704895 0.1963016 0.07623541 0.03130918 0.2138678 0.1113118 0.03376823 0.2096877 0.1131524 0.0952059 0.209244 0.0815891 0.09413427 0.2141346 0.08308571 0.1099207 0.2082172 0.07131099 0.08773094 0.2289582 0.04087024 0.07354378 0.2207859 0.04627656 0.07299298 0.2155166 0.04566788 0.1191781 0.201792 0.05256003 0.08209931 0.1923325 0.06724059 0.08213359 0.1931388 0.0613169 0.1050116 0.2415917 0.04454129 0.0807085 0.1948313 0.05641174 0.07245886 0.2342244 0.06830906 0.07882261 0.1975331 0.05231386 0.07753133 0.2346768 0.07143759 0.07691478 0.2011659 0.04908186 0.07523751 0.2055515 0.04682546 0.08139795 0.2335982 0.07500439 0.07396978 0.2104545 0.0456295 0.08478057 0.23128 0.07828873 0.08778369 0.2279288 0.08093565 0.09038621 0.2237752 0.08270668 0.0925222 0.2190807 0.08345061 0.1127285 0.2048565 0.06601756 0.1122914 0.2018582 0.06169009 0.09202498 0.2337483 0.04181653 0.09436118 0.2372382 0.04508316 0.1181144 0.2198379 0.06960171 0.1169806 0.2248941 0.06971472 0.1186168 0.2148185 0.06841111 0.09588336 0.226127 0.03370791 0.09638577 0.2211076 0.03251731 0.1362746 0.2052215 0.0360586 0.1231656 0.2029333 0.03795129 0.1271018 0.2472245 0.03685653 0.1065939 0.2010148 0.04193764 0.1193673 0.2446631 0.04761064 0.1038918 0.2035087 0.03828477 0.1013849 0.2069885 0.03537434 0.1079063 0.2399306 0.06018137 0.09921884 0.2112519 0.03337544 0.09751957 0.2160513 0.0324043 0.1106083 0.2374367 0.06383424 0.1131153 0.2339569 0.06674474 0.1152813 0.2296935 0.06874358 0.1374728 0.2348959 0.05527693 0.1352415 0.239144 0.05331766 0.1391934 0.2301015 0.05623513 0.1403033 0.2250396 0.0561366 0.1407379 0.2200044 0.05498713 0.1166317 0.230991 0.02111703 0.1170663 0.2259557 0.01996755 0.1404721 0.2152884 0.0528534 0.1168975 0.235707 0.02325075 0.1395212 0.2111657 0.04985946 0.1178483 0.2398297 0.02624469 0.1516531 0.2110186 0.0372734 0.1327028 0.2461616 0.02130383 0.1275821 0.2059351 0.02920114 0.1247405 0.2083963 0.02563297 0.1221281 0.2118514 0.02278649 0.1297875 0.2450603 0.04690301 0.1198968 0.2160995 0.02082723 0.1181762 0.2208939 0.01986902 0.132629 0.2425991 0.05047118 0.1615463 0.2298989 0.04183 0.1604608 0.2349663 0.04191213 0.1619052 0.2248463 0.04073148 0.1361819 0.2354631 0.007950484 0.1365408 0.2304105 0.006851971 0.1615166 0.2201022 0.03868043 0.1604032 0.2159423 0.03579598 0.1365703 0.2402071 0.01000154 0.1376839 0.244367 0.01288598 0.1562988 0.2102942 0.02823626 0.1417882 0.2500151 0.02044564 0.1505324 0.2091959 0.01978421 0.1474318 0.2104756 0.0158329 0.1475546 0.2511134 0.02889776 0.1444247 0.212899 0.01237601 0.1416863 0.2163252 0.009614527 0.1506553 0.2498337 0.03284907 0.1393754 0.2205552 0.007708907 0.1376263 0.225343 0.006769835 0.1536622 0.2474102 0.0363059 0.1564007 0.2439841 0.03906738 0.1587117 0.2397541 0.04097306 0.1811679 0.239572 0.02606278 0.1793765 0.2443504 0.02515614 0.1822274 0.2344987 0.02600061 0.1824935 0.2294255 0.02497315 0.1819506 0.2246471 0.02304017 0.1546559 0.239572 -0.006189525 0.154922 0.2344987 -0.007216989 0.1920835 0.222837 0.01094669 0.1551986 0.2443504 -0.004256606 0.1900779 0.2195233 0.007606804 0.1679721 0.250952 -0.01089769 0.1875031 0.2172014 0.003856658 0.1700079 0.254416 -0.007515728 0.1845132 0.2159993 -1.01853e-4 0.1726415 0.2568442 -0.003665208 0.1812695 0.2159821 -0.004045248 0.1757233 0.2580881 4.14284e-4 0.1779596 0.2171555 -0.007760822 0.1790641 0.2580713 0.004477024 0.1630983 0.2170524 -0.001916646 0.160192 0.2204413 -0.004549682 0.1824644 0.2567986 0.008274555 0.1577728 0.2246471 -0.006372511 0.1559814 0.2294255 -0.007279157 0.1740511 0.2519452 0.02070021 0.1769574 0.2485563 0.02333331 0.1663473 0.237 -0.01660877 0.1660812 0.2420732 -0.01558136 0.1666241 0.2468517 -0.01364839 0.1745236 0.2195536 -0.01130843 0.1716173 0.2229425 -0.01394146 0.1691982 0.2271482 -0.01576435 0.1674067 0.2319267 -0.016671 0.1854764 0.2544464 0.01130843 0.1883827 0.2510575 0.01394146 0.1908017 0.2468517 0.01576435 0.1925932 0.2420732 0.016671 0.1936527 0.237 0.01660877 0.1939188 0.2319267 0.01558136 0.1933759 0.2271482 0.01364839 + + + + + + + + + + 0.4709905 0.3343202 0.8163321 0.5432956 0.1050295 0.832946 0.5433049 0.1050206 0.8329409 0.5840556 -0.130352 0.8011789 0.584062 -0.1303601 0.8011728 0.5908976 -0.3582063 0.7228612 0.5908949 -0.3581861 0.7228735 -0.5840611 0.1303651 -0.8011727 -0.5840602 0.1303645 -0.8011735 0.5634036 -0.5652307 0.6025701 0.563405 -0.5652505 0.60255 -0.5908948 0.3581861 -0.7228735 -0.5908946 0.3581832 -0.7228751 0.5054599 -0.7279043 0.4633204 0.5031654 -0.7394783 0.4472098 -0.5634 0.5652486 -0.6025567 -0.563406 0.5652447 -0.6025548 0.4138809 -0.8686212 0.2723965 0.4121512 -0.8711373 0.2669292 -0.4938583 0.7521909 -0.4362487 -0.5031614 0.7394859 -0.4472017 0.305001 -0.9487133 0.0831725 0.2995069 -0.951564 0.0694397 -0.4085844 0.8742253 -0.2622764 -0.4121694 0.8711295 -0.2669264 0.1740031 -0.9763897 -0.1280089 -0.2911814 0.9548091 -0.05960887 -0.2995018 0.9515665 -0.06942641 0.01887381 -0.9412532 -0.3371739 -0.1671801 0.9761726 0.1383398 -0.1142279 -0.8588487 -0.4993305 -0.114227 -0.8588488 -0.4993304 -0.2500461 -0.7225066 -0.6445628 -0.2500404 -0.7225158 -0.6445546 -0.03679823 0.9487338 0.3139271 -0.371304 -0.5442126 -0.752307 -0.3713026 -0.544218 -0.7523039 -0.4709854 -0.3343254 -0.8163329 -0.4709904 -0.3343116 -0.8163356 0.1142297 0.8588494 0.4993289 -0.5432977 -0.1050289 -0.8329446 0.114224 0.8588504 0.4993286 -0.5433027 -0.1050372 -0.8329402 0.2500372 0.7225124 0.6445598 0.2500418 0.722516 0.644554 0.3713077 0.5442104 0.7523069 0.371306 0.5442147 0.7523047 0.4709806 0.3343288 0.8163343 0.4366078 0.325294 0.8387833 0.5075473 0.09560769 0.8563032 0.5075545 0.09560292 0.8562995 0.5490112 -0.1396515 0.8240657 0.5490037 -0.139632 0.8240741 0.5585715 -0.3667794 0.7439562 0.5585696 -0.3667939 0.7439506 -0.5490062 0.1396405 -0.8240708 -0.5490114 0.1396487 -0.8240661 0.5356707 -0.5726197 0.6206156 0.5356728 -0.572605 0.6206274 -0.5585663 0.3667815 -0.7439591 -0.5585695 0.3667727 -0.743961 0.4760355 -0.7573099 0.4470704 -0.5356701 0.572621 -0.6206148 -0.5356684 0.5726211 -0.6206163 -0.487289 0.732306 -0.4756863 0.1691841 -0.9759819 -0.1372453 0.03843086 -0.940676 -0.3371225 0.0519132 -0.949594 -0.3091542 -0.1737721 0.9761447 0.1301727 -0.08753502 -0.8602131 -0.5023655 -0.0933507 -0.8533713 -0.5128774 -0.224193 -0.7157631 -0.661378 -0.2241988 -0.7157554 -0.6613842 -0.04372018 0.9430959 0.3296343 -0.01850384 0.9346315 0.3551362 -0.3402915 -0.5360928 -0.7725324 -0.3402917 -0.5360996 -0.7725276 -0.4366022 -0.3252956 -0.8387855 -0.4366073 -0.3252995 -0.8387815 0.08817517 0.856675 0.5082648 -0.5075497 -0.09560334 -0.8563022 0.09334003 0.8533673 0.5128861 -0.5075506 -0.09560155 -0.8563019 0.2214745 0.7150155 0.6631002 0.2352797 0.7011648 0.6730613 0.3402894 0.5360971 0.7725304 0.340292 0.5360962 0.7725297 0.4366081 0.3252919 0.838784 0.4786792 0.09053301 0.8733099 0.409271 0.3182113 0.855125 0.5207242 -0.1446031 0.8413894 0.4788564 0.0881645 0.873455 -0.5210871 0.148458 -0.840493 0.5325284 -0.3714372 0.7605577 0.5206164 -0.147025 0.8410364 0.5321301 -0.3736474 0.7597535 0.513772 -0.5745689 0.6371099 -0.5320836 0.3731673 -0.7600219 -0.5206837 0.1469966 -0.8409997 0.463894 -0.7485308 0.4738185 0.5123655 -0.578673 0.6345229 -0.5123456 0.5825594 -0.6309728 -0.5321521 0.3736413 -0.7597411 0.3877939 -0.8785752 0.2787861 0.4738273 -0.7312765 0.4906346 -0.4627074 0.7514092 -0.4704106 -0.5123934 0.5786676 -0.6345052 0.2815938 -0.9576699 0.05977857 0.3916071 -0.874897 0.2849546 -0.3901733 0.8758412 -0.2840198 -0.4593753 0.7652962 -0.4508836 -0.2999618 0.9492102 -0.09498947 -0.3878998 0.8791959 -0.2766738 -0.2054989 -0.7092947 -0.6742931 -0.09370702 -0.8378199 -0.5378446 -0.3171845 -0.5281057 -0.7877172 -0.2041656 -0.7105844 -0.6733397 -0.4104474 -0.3161774 -0.8553157 -0.3159243 -0.5297875 -0.7870942 -0.4792308 -0.08838224 -0.8732276 -0.4093009 -0.3182222 -0.8551068 -0.4792774 -0.08826845 -0.8732136 0.1883556 0.7315025 0.6553063 0.3153173 0.5316285 0.7860955 0.3158953 0.5297816 0.7871096 0.4088543 0.3203956 0.8545086 0.4971545 -0.1524573 0.8541629 0.4557381 0.0835433 0.8861848 0.4971195 -0.1517465 0.8543098 0.5093967 -0.3880773 0.7680568 0.49132 -0.5911348 0.6396597 0.5101189 -0.3781933 0.7724952 -0.509544 0.3709674 -0.7763687 -0.4967939 0.1506653 -0.8546904 -0.496487 0.1442409 -0.8559762 -0.4939047 0.5759224 -0.6514381 -0.5100798 0.3815336 -0.7708766 0.2689455 -0.9612929 0.05986857 0.3771323 -0.8772534 0.2969809 0.1733378 -0.9759974 -0.1318448 0.2913162 -0.951676 0.09719991 0.05144083 -0.9393598 -0.3390533 0.1699773 -0.9758569 -0.1371542 -0.2886021 0.9522 -0.1001204 -0.370972 0.8847086 -0.2822597 -0.07234472 -0.8476592 -0.5255857 0.05106329 -0.9391871 -0.3395882 -0.170986 0.9758269 0.1361089 -0.1907106 -0.7064992 -0.6815339 -0.2745429 0.9595342 -0.06261283 -0.06709784 -0.8520221 -0.5191884 -0.2983739 -0.5244131 -0.7974735 -0.1904689 -0.7067912 -0.6812987 -0.05115717 0.9392135 0.3395011 -0.3885989 -0.3119599 -0.8669902 -0.1737902 0.9761349 0.1302219 -0.2982664 -0.5245809 -0.7974033 -0.4562427 -0.08132779 -0.8861312 -0.388637 -0.3118751 -0.8670037 0.07176351 0.8482056 0.5247831 -0.4569907 -0.07889628 -0.8859655 -0.05148136 0.9394132 0.3388993 0.1906151 0.7079582 0.6800449 0.070885 0.8491755 0.5233319 0.1968606 0.697586 0.6889265 0.297522 0.5261112 0.796673 0.2976007 0.5259087 0.7967772 0.3879248 0.3138388 0.8666138 0.4557998 0.08317613 0.8861876 0.3879131 0.3138854 0.8666023 0.4910327 -0.5937609 0.637444 0.4452252 -0.756454 0.4791158 0.4449673 -0.757251 0.4780953 -0.4946575 0.5725902 -0.6538 0.3724014 -0.8824805 0.2873072 -0.4468925 0.7522933 -0.4840887 -0.4473176 0.7513747 -0.4851216 -0.3745467 0.8798866 -0.2924284 0.4721749 0.08627223 0.877273 0.4049637 0.3199909 0.8565106 0.5114033 -0.1495445 0.8462288 0.471989 0.08912098 0.8770883 -0.5114447 0.1495354 -0.8462054 0.5214577 -0.3438882 0.7809115 0.511544 -0.1469821 0.8465926 -0.519954 0.4051666 -0.7519894 -0.5119127 0.1511991 -0.8456266 0.1499878 -0.9781838 -0.1437364 0.2800291 -0.9556196 0.09151566 0.02421814 -0.9364328 -0.35001 0.1582495 -0.978499 -0.1322756 -0.1684699 0.9793133 0.1120873 -0.2698957 0.9601923 -0.07202148 -0.08604127 -0.8513118 -0.517557 0.03720617 -0.9412744 -0.3355864 -0.206646 -0.7110214 -0.6721205 -0.08825802 -0.8497922 -0.5196767 -0.0479145 0.9484233 0.3133648 -0.1633886 0.9788196 0.123355 -0.3152294 -0.5294244 -0.787617 -0.2086859 -0.708947 -0.6736798 -0.4054887 -0.3170558 -0.8573533 -0.3170109 -0.5269514 -0.7885597 0.08604609 0.8513082 0.5175622 -0.4721677 -0.08626526 -0.8772777 -0.04097157 0.9432069 0.3296699 -0.4069171 -0.3144167 -0.8576484 -0.4728386 -0.08459907 -0.8770785 0.08476972 0.8530936 0.5148258 0.2066558 0.7110233 0.6721155 0.2055569 0.7133753 0.6699567 0.3152394 0.5294241 0.787613 0.3143954 0.5321725 0.7860968 0.4054939 0.3170552 0.8573511 0.3426451 0.535868 0.7716476 0.4341934 0.323827 0.8406023 0.4341919 0.3238263 0.8406033 0.5005157 0.09299379 0.8607185 0.500517 0.09299731 0.8607174 0.5377663 -0.1432598 0.8308334 -0.5377659 0.1432595 -0.8308337 0.5377684 -0.1432523 0.8308333 -0.5377656 0.1432533 -0.8308351 0.54292 -0.3880386 0.7447576 0.5415703 -0.3716784 0.7540271 -0.541527 0.3716878 -0.7540536 -0.5444151 0.3549845 -0.7599989 0.5169475 -0.577866 0.6315349 0.5171945 -0.5714439 0.6371513 -0.5169222 0.5778626 -0.6315587 0.4576538 -0.7667887 0.4500981 -0.5142551 0.5849111 -0.6272326 0.4619643 -0.750185 0.4730872 -0.4747038 0.7301922 -0.4914017 0.3885158 -0.8714489 0.2993866 -0.4615905 0.750983 -0.4721851 -0.3758237 0.8853386 -0.2737372 0.03598052 -0.9507114 -0.3079826 -0.1062747 -0.8560553 -0.505841 -0.1062749 -0.8560575 -0.5058372 -0.2311844 -0.7167732 -0.6578677 -0.01257205 0.9395294 0.3422378 -0.2311835 -0.7167782 -0.6578627 -0.3426426 -0.5358657 -0.7716503 -0.3426432 -0.5358675 -0.7716488 0.1062731 0.856054 0.5058435 -0.4341928 -0.3238267 -0.8406027 -0.4341943 -0.3238271 -0.8406018 0.1062743 0.8560566 0.5058388 -0.5005178 -0.0929979 -0.8607169 -0.5005194 -0.09299457 -0.8607162 0.2311833 0.716776 0.6578651 0.2311843 0.7167748 0.6578661 0.342644 0.5358642 0.7716505 0.5395276 0.1020296 0.8357631 0.4731931 0.3328378 0.8156637 0.5745249 -0.134717 0.8073242 0.5395272 0.1020354 0.8357626 -0.5745252 0.134717 -0.8073241 0.576156 -0.3636643 0.7319785 0.574527 -0.1347119 0.8073238 0.5761557 -0.3636511 0.7319853 0.5443095 -0.5714941 0.6141025 -0.5761591 0.3636472 -0.7319847 -0.5745263 0.1347156 -0.8073235 0.4902155 -0.7268426 0.4810287 0.5443074 -0.5715054 0.6140938 -0.5443084 0.5715127 -0.614086 -0.5761569 0.3636526 -0.7319837 -0.4721347 0.7627214 -0.4419785 -0.5443038 0.5714994 -0.6141026 0.276722 -0.9569288 0.08781898 0.3768611 -0.8875889 0.2648805 -0.2726235 0.9587089 -0.08095425 -0.3962853 0.8671408 -0.3017035 0.008640289 -0.9493085 -0.3142276 0.1566382 -0.982306 -0.1026618 -0.1323063 -0.8620518 -0.489246 -0.003284692 -0.9453737 -0.3259721 -0.2635008 -0.7242197 -0.6372388 -0.1323035 -0.8620554 -0.4892407 -0.00863111 0.9493081 0.3142288 -0.1328206 0.9814533 0.1382321 -0.379377 -0.5443199 -0.7481904 -0.2635051 -0.7242173 -0.6372396 -0.4731881 -0.3328453 -0.8156635 -0.3793691 -0.5443373 -0.7481819 0.1323076 0.8620498 0.4892493 -0.5395305 -0.1020317 -0.835761 -0.01596629 0.9537342 0.300227 -0.4731941 -0.3328377 -0.8156632 -0.5395247 -0.1020362 -0.8357641 0.132305 0.8620516 0.4892467 0.2634992 0.724227 0.6372312 0.2635031 0.7242195 0.6372381 0.3793714 0.5443282 0.7481873 0.3793695 0.5443342 0.7481839 0.4731881 0.3328469 0.8156629 0.5213865 0.3436629 0.7810583 0.5879433 0.1129717 0.8009745 0.5879487 0.1129651 0.8009714 0.6203685 -0.1242954 0.7743989 0.6203731 -0.1242982 0.7743948 0.6167817 -0.3543928 0.7028416 0.6167808 -0.3543855 0.7028459 -0.6203708 0.1242954 -0.7743971 -0.6203699 0.1243008 -0.774397 0.5745894 -0.587876 0.5694285 0.5773596 -0.5639367 0.5904502 -0.6167839 0.3543779 -0.7028471 -0.6167834 0.3543789 -0.7028469 0.5028482 -0.7454165 0.4376051 0.4974272 -0.7567059 0.4242196 -0.590605 0.5351947 -0.6039473 -0.5773524 0.563959 -0.5904359 0.4020249 -0.8760249 0.2663764 0.4081321 -0.8690953 0.2794669 -0.508463 0.7356925 -0.4474619 -0.5181687 0.7208536 -0.4602949 0.2758128 -0.9576637 0.08250772 0.2735067 -0.958665 0.07845824 -0.4059807 0.8723326 -0.2724252 -0.3976709 0.8790316 -0.2629853 0.134833 -0.9851143 -0.1066297 0.1156435 -0.9835344 -0.1388763 -0.2762948 0.9574633 -0.08321809 -0.2811297 0.9555245 -0.08910161 -0.01431632 -0.9570732 -0.2894926 -0.01799649 -0.9552506 -0.29525 -0.1309336 0.9850743 0.1117364 -0.1517594 0.9842268 0.09092164 -0.187653 -0.8500244 -0.492184 -0.1680206 -0.8699173 -0.4636949 -0.303051 -0.7330309 -0.6089547 -0.3030507 -0.7330358 -0.608949 0.02253741 0.9538291 0.2995035 0.0179311 0.9552376 0.295296 -0.4245547 -0.5544345 -0.7157903 -0.4245622 -0.5544195 -0.7157974 -0.5213848 -0.3436632 -0.7810593 -0.5213869 -0.3436732 -0.7810534 0.1407911 0.8861656 0.4414616 -0.5879443 -0.1129541 -0.8009763 0.1678586 0.8698843 0.4638155 -0.5879439 -0.1129634 -0.8009753 0.3030475 0.7330404 0.608945 0.303054 0.733033 0.6089507 0.424556 0.5544259 0.7157962 0.4245624 0.5544233 0.7157943 0.5213836 0.3436664 0.7810587 -0.6459048 0.1188474 -0.7541103 -0.6459106 0.1188462 -0.7541056 -0.639423 0.3496342 -0.6847585 -0.6394218 0.3496428 -0.6847552 -0.16574 -0.8840318 -0.4370562 -0.5912162 0.574262 -0.5662921 -0.3246716 -0.7380309 -0.5915225 -0.3246721 -0.7380351 -0.591517 -0.4494213 -0.5601215 -0.6959055 -0.44943 -0.5601145 -0.6959055 -0.6148571 -0.1188379 -0.7796334 -0.5480639 -0.3496397 -0.759854 -0.5480654 -0.3496428 -0.7598515 -0.614854 -0.1188515 -0.7796338 0.1981486 0.8600814 0.4701035 0.3246733 0.7380321 0.59152 0.3246727 0.7380314 0.5915212 0.4494285 0.5601139 0.6959069 0.4494317 0.5601033 0.6959134 0.5480663 0.3496473 0.7598487 0.5480626 0.3496443 0.7598528 0.6148568 0.1188433 0.7796329 0.6148528 0.1188546 0.7796342 0.6459085 -0.118846 0.7541073 0.6459083 -0.1188456 0.7541076 0.6394256 -0.3496451 0.6847506 0.6394208 -0.3496432 0.684756 0.6000434 -0.5461664 0.5845085 -0.7912291 -0.2120198 0.573589 -0.7912451 -0.2120211 0.5735663 -0.7912506 -0.212017 0.5735604 -0.791806 -0.2059074 0.5750178 -0.7912372 -0.2120091 0.5735818 -0.7912389 -0.2120121 0.5735782 -0.7912364 -0.2120094 0.5735826 -0.7912439 -0.2120131 0.5735708 -0.7912372 -0.21201 0.5735812 -0.7912304 -0.2120209 0.5735866 -0.7912162 -0.2120504 0.5735953 -0.7912587 -0.2119925 0.573558 -0.7912489 -0.2120022 0.5735682 -0.7907204 -0.2171642 0.5723645 -0.791243 -0.2120091 0.5735736 -0.7912403 -0.2120129 0.573576 -0.7912432 -0.2120081 0.5735737 -0.7912042 -0.2119939 0.573633 -0.7912392 -0.2120111 0.5735782 -0.7912416 -0.2120126 0.5735743 -0.7912435 -0.2120144 0.573571 -0.7912392 -0.212014 0.5735772 -0.7912416 -0.2120128 0.5735743 -0.7912483 -0.2120135 0.5735648 0.7609568 0.1650348 -0.6274619 0.7616768 0.1667403 -0.626136 0.7616922 0.1667565 -0.6261129 0.76169 0.1669571 -0.6260621 0.7620613 0.1656709 -0.625952 0.7615431 0.167038 -0.6262192 0.7708312 0.1559736 -0.6176502 0.7503708 0.1799887 -0.6360407 0.761711 0.1668242 -0.626072 0.76169 0.16674 -0.6261199 0.7616885 0.1667501 -0.626119 0.7616033 0.1670411 -0.6261453 0.7616873 0.1667476 -0.6261211 0.7616811 0.1666767 -0.6261476 0.7617603 0.166707 -0.6260432 0.7619818 0.1660837 -0.6259393 0.7617077 0.1667418 -0.6260979 0.761716 0.1623446 -0.6272424 0.761418 0.167536 -0.6262384 0.7617066 0.1667598 -0.6260945 0.7619051 0.1652171 -0.626262 0.7616974 0.1667531 -0.6261075 0.7616867 0.1667473 -0.6261221 0.7616912 0.1667505 -0.6261158 + + + + + + + + + + + + + + +

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

+
+
+
+ + + + 0.1856576 -0.1985 -0.01368701 0.1904539 -0.1985 -0.01048225 0.1936587 -0.1985 -0.005685925 0.18 -0.1985 -0.0148124 0.1743423 -0.1985 -0.01368701 0.1947841 -0.1985 -2.83448e-5 0.1936587 -0.1985 0.005629241 0.1663413 -0.1985 -0.005685925 0.1695461 -0.1985 -0.01048225 0.1652159 -0.1985 -2.83448e-5 0.1904539 -0.1985 0.01042556 0.1856576 -0.1985 0.01363033 0.18 -0.1985 0.01475572 0.1663413 -0.1985 0.005629241 0.1743423 -0.1985 0.01363033 0.1695461 -0.1985 0.01042556 0.1681042 -0.1965 -0.01192414 0.173562 -0.1965 -0.01557099 0.18 -0.1965 -0.0168516 0.186438 -0.1965 -0.01557099 0.1918958 -0.1965 -0.01192414 0.1955426 -0.1965 -0.006466269 0.1968232 -0.1965 -2.83448e-5 0.1955426 -0.1965 0.006409585 0.1918958 -0.1965 0.01186746 0.186438 -0.1965 0.01551431 0.18 -0.1965 0.01679486 0.173562 -0.1965 0.01551431 0.1681042 -0.1965 0.01186746 0.1644573 -0.1965 0.006409585 0.1631767 -0.1965 -2.83448e-5 0.1644573 -0.1965 -0.006466269 0.1681042 -0.184 -0.01192414 0.173562 -0.184 -0.01557099 0.18 -0.184 -0.0168516 0.186438 -0.184 -0.01557099 0.1918958 -0.184 -0.01192414 0.1955426 -0.184 -0.006466269 0.1968232 -0.184 -2.83448e-5 0.1955426 -0.184 0.006409585 0.1918958 -0.184 0.01186746 0.186438 -0.184 0.01551431 0.18 -0.184 0.01679486 0.173562 -0.184 0.01551431 0.1681042 -0.184 0.01186746 0.1644573 -0.184 0.006409585 0.1631767 -0.184 -2.83448e-5 0.1644573 -0.184 -0.006466269 0.2391806 -0.184 0.03997164 0.2391806 -0.007999956 0.03997164 0.23 -0.007999956 0.03997164 0.23 -0.184 0.03997164 0.22 -0.184 0.04997164 0.22 -0.007999956 0.04997164 0.22 -0.007999956 0.05915224 0.22 -0.184 0.05915224 0.22 -0.007999956 -0.05002832 0.22 -0.184 -0.05002832 0.22 -0.184 -0.05920892 0.22 -0.007999956 -0.05920892 0.23 -0.007999956 -0.04002833 0.23 -0.184 -0.04002833 0.2391806 -0.007999956 -0.04002833 0.2391806 -0.184 -0.04002833 0.1299999 -0.007999956 -0.04002833 0.1299999 -0.184 -0.04002833 0.1208194 -0.184 -0.04002833 0.1208194 -0.007999956 -0.04002833 0.14 -0.184 -0.05002832 0.14 -0.007999956 -0.05002832 0.14 -0.007999956 -0.05920892 0.14 -0.184 -0.05920892 0.14 -0.184 0.05915224 0.14 -0.007999956 0.05915224 0.14 -0.007999956 0.04997164 0.14 -0.184 0.04997164 0.1299999 -0.184 0.03997164 0.1299999 -0.007999956 0.03997164 0.1208194 -0.007999956 0.03997164 0.1208194 -0.184 0.03997164 0.216 -0.007999956 0.06315225 0.216 -0.184 0.06315225 0.1439999 -0.007999956 0.06315225 0.1439999 -0.184 0.06315225 0.2431806 -0.007999956 -0.03602832 0.2431806 -0.184 -0.03602832 0.2431806 -0.007999956 0.03597164 0.2431806 -0.184 0.03597164 0.1439999 -0.007999956 -0.06320893 0.1439999 -0.184 -0.06320893 0.216 -0.007999956 -0.06320893 0.216 -0.184 -0.06320893 0.1168194 -0.007999956 0.03597164 0.1168194 -0.184 0.03597164 0.1168194 -0.184 -0.03602832 0.1168194 -0.007999956 -0.03602832 0.2431806 -0.007999956 0.05315226 0.2331806 -0.007999956 0.06315225 0.2331806 -0.007999956 -0.06320893 0.2431806 -0.007999956 -0.05320894 0.1268194 -0.007999956 -0.06320893 0.1168194 -0.007999956 -0.05320894 0.1268194 -0.007999956 0.06315225 0.1168194 -0.007999956 0.05315226 0.1268194 0.003999948 0.06315225 0.1168194 0.003999948 0.05315226 0.1168194 0.003999948 -0.05320894 0.1268194 0.003999948 -0.06320893 0.2331806 0.003999948 -0.06320893 0.2431806 0.003999948 -0.05320894 0.2431806 0.003999948 0.05315226 0.2331806 0.003999948 0.06315225 + + + + + + + + + + 0 -1 0 0 -1 3.65688e-5 0 -1 -1.28414e-5 0 -1 1.82844e-5 -0.3928501 -0.7071027 -0.5879412 -0.3928512 -0.7071061 -0.5879362 -0.1379486 -0.7071018 -0.6935252 -0.1379514 -0.7071095 -0.6935169 0.13795 -0.7071025 -0.6935243 0.1379507 -0.7071049 -0.6935217 0.392849 -0.7071115 -0.5879313 0.3928501 -0.7071027 -0.5879412 0.5879413 -0.7071001 -0.3928544 0.5879345 -0.7071076 -0.3928511 0.6935222 -0.7071045 -0.1379503 0.6935179 -0.7071078 -0.1379545 0.6935176 -0.7071075 0.1379581 0.6935184 -0.7071084 0.1379495 0.5879332 -0.7071092 0.3928503 0.5879428 -0.7070983 0.3928554 0.3928489 -0.7071127 0.5879297 0.3928501 -0.7071027 0.5879412 0.1379489 -0.7071035 0.6935235 0.1379503 -0.7071033 0.6935234 -0.1379473 -0.7071043 0.693523 -0.1379505 -0.7071096 0.6935169 -0.392851 -0.7071009 0.5879426 -0.3928511 -0.7071074 0.5879347 -0.5879333 -0.7071118 0.3928455 -0.5879358 -0.707106 0.392852 -0.6935161 -0.7071107 0.137949 -0.6935117 -0.7071141 0.1379534 -0.6935074 -0.7071186 -0.1379525 -0.6935222 -0.7071045 -0.1379503 -0.5879391 -0.7071046 -0.3928494 -0.5879312 -0.7071115 -0.392849 -0.5555734 0 -0.8314676 -0.5555731 0 -0.8314678 -0.1950908 0 -0.9807853 -0.1950907 0 -0.9807853 0.1950902 0 -0.9807853 0.195092 0 -0.980785 0.5555734 0 -0.8314676 0.5555731 0 -0.8314678 0.8314642 0 -0.5555785 0.8314648 0 -0.5555775 0.9807849 0 -0.1950923 0.980785 0 -0.195092 0.9807849 0 0.1950923 0.980785 0 0.195092 0.8314641 0 0.5555785 0.8314647 0 0.5555776 0.5555743 0 0.831467 0.1950892 0 0.9807856 0.1950902 0 0.9807853 -0.1950892 0 0.9807856 -0.1950897 0 0.9807855 -0.5555743 0 0.831467 -0.8314641 0 0.5555786 -0.8314648 0 0.5555775 -0.9807849 0 0.1950923 -0.980785 0 0.195092 -0.9807849 0 -0.1950923 -0.980785 0 -0.195092 -0.8314642 0 -0.5555785 -0.8314648 0 -0.5555775 0 0 1 0.7071067 0 0.7071069 0.7071063 0 0.7071073 1 0 0 0.7071063 0 -0.7071073 0.7071065 0 -0.7071071 0 0 -1 -0.7071065 0 -0.7071071 -0.7071063 0 -0.7071073 -1 0 0 -0.7071063 0 0.7071073 -0.7071067 0 0.7071069 0.7071073 0 0.7071063 -0.7071073 0 0.7071063 0.7071065 0 -0.7071071 0.7071059 0 -0.7071076 0.7071059 0 0.7071076 0.7071065 0 0.7071071 -0.7071073 0 -0.7071063 -0.7071082 0 -0.7071053 0.7071082 0 -0.7071053 0.7071073 0 -0.7071063 -0.7071071 0 0.7071065 -0.7071066 0 0.707107 0 -1 2.99987e-6 0 -1 -2.63765e-6 0 -1 -3.51687e-6 0 -1 3.51689e-6 0 -1 -2.63766e-6 0 -1 2.99986e-6 0 -1 -2.99985e-6 0 -1 3.51688e-6 0 -1 -2.52775e-6 0 -1 -3.5281e-7 -0.7071066 0 -0.707107 -0.7071071 0 -0.7071065 0 -1 0 0 -1 0 0 -1 -4.23498e-7 0 -1 2.11749e-7 0 -1 2.11749e-7 0 -1 0 0 -1 -1.20258e-7 0 -1 -4.23499e-7 0 -1 0 -0.7071068 0 0.7071067 -0.7071066 0 0.7071071 -0.7071066 0 -0.7071071 -0.7071068 0 -0.7071067 -1 1.07792e-6 0 0.7071068 0 -0.7071067 0.7071066 0 -0.7071071 0.7071066 0 0.7071071 0.7071068 0 0.7071067 1 -4.31168e-6 0 1 2.91874e-6 0 0 1 0 0 1 0 0 1 0 + + + + + + + + + + + + + + +

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

+
+
+
+ + + + 0.01045387 0.01045387 -0.08849996 0.0136587 0.005657613 -0.08849996 0.01478403 0 -0.08849996 0.005657613 0.0136587 -0.08849996 0 0.01478403 -0.08849996 0.0136587 -0.005657613 -0.08849996 -0.005657613 0.0136587 -0.08849996 0.01045387 -0.01045387 -0.08849996 0.005657613 -0.0136587 -0.08849996 -0.0136587 0.005657613 -0.08849996 -0.01045387 0.01045387 -0.08849996 -0.01478403 0 -0.08849996 0 -0.01478403 -0.08849996 -0.005657613 -0.0136587 -0.08849996 -0.0136587 -0.005657613 -0.08849996 -0.01045387 -0.01045387 -0.08849996 -0.01189583 0.01189583 -0.08649998 -0.006437957 0.01554262 -0.08649998 0 0.01682323 -0.08649998 0.006437957 0.01554262 -0.08649998 0.01189583 0.01189583 -0.08649998 0.01554262 0.006437957 -0.08649998 0.01682323 0 -0.08649998 0.01554262 -0.006437957 -0.08649998 0.01189583 -0.01189583 -0.08649998 0.006437957 -0.01554262 -0.08649998 0 -0.01682323 -0.08649998 -0.006437957 -0.01554262 -0.08649998 -0.01189583 -0.01189583 -0.08649998 -0.01554262 -0.006437957 -0.08649998 -0.01682323 0 -0.08649998 -0.01554262 0.006437957 -0.08649998 -0.01189583 0.01189583 -0.074 -0.006437957 0.01554262 -0.074 0 0.01682323 -0.074 0.006437957 0.01554262 -0.074 0.01189583 0.01189583 -0.074 0.01554262 0.006437957 -0.074 0.01682323 0 -0.074 0.01554262 -0.006437957 -0.074 0.01189583 -0.01189583 -0.074 0.006437957 -0.01554262 -0.074 0 -0.01682323 -0.074 -0.006437957 -0.01554262 -0.074 -0.01189583 -0.01189583 -0.074 -0.01554262 -0.006437957 -0.074 -0.01682323 0 -0.074 -0.01554262 0.006437957 -0.074 -0.04999995 -0.03999996 -0.074 -0.06318056 -0.03599995 -0.074 -0.06318056 0.03599995 -0.074 -0.05918055 -0.03999996 -0.074 0.03599995 -0.06318056 -0.074 -0.03599995 -0.06318056 -0.074 -0.03999996 -0.04999995 -0.074 -0.03999996 -0.05918055 -0.074 0.05918055 0.03999996 -0.074 0.06318056 0.03599995 -0.074 0.04999995 0.03999996 -0.074 0.03599995 0.06318056 -0.074 0.03999996 0.05918055 -0.074 0.03999996 0.04999995 -0.074 0.06318056 -0.03599995 -0.074 -0.03599995 0.06318056 -0.074 -0.03999996 0.05918055 -0.074 -0.03999996 0.04999995 -0.074 0.05918055 -0.03999996 -0.074 0.04999995 -0.03999996 -0.074 0.03999996 -0.04999995 -0.074 -0.04999995 0.03999996 -0.074 -0.05918055 0.03999996 -0.074 0.03999996 -0.05918055 -0.074 -0.03599995 -0.06318056 0.104 -0.03999996 -0.05918055 0.104 0.03999996 -0.05918055 0.104 0.03599995 -0.06318056 0.104 0.06318056 -0.03599995 0.104 0.05918055 -0.03999996 0.104 0.05918055 0.03999996 0.104 0.06318056 0.03599995 0.104 -0.03999996 0.05918055 0.104 -0.03599995 0.06318056 0.104 -0.06318056 0.03599995 0.104 -0.05918055 0.03999996 0.104 -0.05918055 -0.03999996 0.104 -0.06318056 -0.03599995 0.104 -0.03999996 -0.04999995 0.104 -0.04999995 -0.03999996 0.104 -0.04999995 0.03999996 0.104 -0.03999996 0.04999995 0.104 0.03599995 0.06318056 0.104 0.03999996 0.05918055 0.104 0.03999996 0.04999995 0.104 0.04999995 0.03999996 0.104 0.04999995 -0.03999996 0.104 0.03999996 -0.04999995 0.104 + + + + + + + + + + 0 0 -1 4.57108e-6 0 -1 -3.76623e-7 0 -1 -2.1334e-7 0 -1 -0.3928473 0.5879391 -0.7071059 -0.3928471 0.5879383 -0.7071065 -0.1379497 0.6935202 -0.7071066 -0.13795 0.6935212 -0.7071056 0.1379481 0.6935212 -0.7071059 0.1379514 0.6935203 -0.7071061 0.3928483 0.587938 -0.7071062 0.3928474 0.5879387 -0.707106 0.5879386 0.3928472 -0.7071063 0.5879365 0.392848 -0.7071077 0.6935191 0.1379502 -0.7071076 0.6935212 0.1379495 -0.7071056 0.6935212 -0.1379495 -0.7071056 0.6935209 -0.1379498 -0.7071059 0.5879364 -0.392848 -0.7071077 0.5879409 -0.3928464 -0.7071049 0.3928472 -0.5879384 -0.7071064 0.3928471 -0.5879389 -0.7071061 0.1379481 -0.6935212 -0.7071059 0.1379514 -0.6935203 -0.7071061 -0.1379498 -0.6935203 -0.7071064 -0.1379481 -0.6935212 -0.7071059 -0.3928474 -0.5879387 -0.707106 -0.3928468 -0.5879384 -0.7071067 -0.5879364 -0.392848 -0.7071077 -0.5879409 -0.3928464 -0.7071049 -0.6935212 -0.1379495 -0.7071056 -0.6935209 -0.1379498 -0.7071059 -0.6935227 0.1379495 -0.7071042 -0.6935212 0.1379495 -0.7071056 -0.5879409 0.3928464 -0.7071049 -0.5879365 0.392848 -0.7071077 -0.5555691 0.8314705 0 -0.5555701 0.8314698 0 -0.1950899 0.9807854 0 0.1950899 0.9807854 0 0.5555691 0.8314704 0 0.55557 0.8314698 0 0.8314698 0.5555701 0 0.8314704 0.5555692 0 0.9807853 0.1950902 0 0.9807855 0.1950896 0 0.9807853 -0.1950902 0 0.9807855 -0.1950896 0 0.8314698 -0.5555701 0 0.8314704 -0.5555692 0 0.5555691 -0.8314704 0 0.55557 -0.8314698 0 0.1950899 -0.9807854 0 0.1950899 -0.9807854 0 -0.1950899 -0.9807854 0 -0.5555691 -0.8314704 0 -0.55557 -0.8314698 0 -0.8314699 -0.5555698 0 -0.8314702 -0.5555695 0 -0.9807854 -0.1950899 0 -0.9807854 -0.1950899 0 -0.9807854 0.1950899 0 -0.9807854 0.1950899 0 -0.8314698 0.5555701 0 -0.8314704 0.5555692 0 3.52811e-7 0 -1 7.03327e-7 0 -1 -1.49992e-6 0 -1 -1.49992e-6 0 -1 -7.05621e-7 0 -1 1.75844e-6 0 -1 1.64854e-7 0 -1 -3.52811e-7 0 -1 -1.64854e-7 0 -1 1.49992e-6 0 -1 5.27495e-7 0 -1 1.49992e-6 0 -1 -7.03327e-7 0 -1 -1.75844e-6 0 -1 7.05621e-7 0 -1 -5.27495e-7 0 -1 -0.7071073 -0.7071063 0 0.7071073 -0.7071063 0 0.7071061 -0.7071076 0 0.707107 -0.7071067 0 0.707107 0.7071067 0 0.7071061 0.7071076 0 -0.7071073 0.7071063 0 -0.7071061 0.7071076 0 -0.707107 0.7071067 0 -0.707107 -0.7071067 0 -0.7071061 -0.7071076 0 -0.7071064 -0.7071072 0 0 -1 0 -1 0 0 -0.7071069 0.7071067 0 -0.7071064 0.7071072 0 0 1 0 0.7071073 0.7071063 0 0.7071064 0.7071072 0 1 0 0 0.7071069 -0.7071067 0 0.7071064 -0.7071072 0 -1.58507e-6 0 1 0 0 1 1.58507e-6 0 1 5.82076e-7 0 1 5.5202e-7 0 1 -3.17015e-6 0 1 3.68013e-7 0 1 + + + + + + + + + + + + + + +

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

+
+
+
+ + + + -0.02662187 0.1867107 0.1444368 -0.04402917 0.1820464 0.1570554 -0.04869717 0.1772649 0.1603487 -0.0277031 0.1898923 0.1441214 -0.02991682 0.1715224 0.1342775 -0.0521332 0.1654629 0.1501236 -0.05366206 0.1650984 0.1471213 -0.02599287 0.1834135 0.1440858 -0.04828047 0.1741085 0.1591698 -0.03179234 0.1710426 0.1315129 -0.05546551 0.165495 0.1442828 -0.0258525 0.1801921 0.1430886 -0.0509808 0.1704319 0.1591284 -0.03381943 0.1713576 0.1288329 -0.05736064 0.1666502 0.1417343 -0.02620899 0.1772339 0.1415035 -0.04864788 0.1688582 0.1549519 -0.03588044 0.1724492 0.1263933 -0.05922234 0.1684982 0.1396129 -0.02704161 0.1747108 0.1394222 -0.0506314 0.166671 0.1529194 -0.02830195 0.1727694 0.1369661 -0.03785544 0.1742539 0.1243359 -0.06093555 0.1709322 0.138034 -0.03962975 0.1766667 0.1227801 -0.06239593 0.1738128 0.1370826 -0.04110026 0.1795478 0.1218165 -0.06351137 0.1769766 0.136807 -0.04218143 0.1827293 0.1215011 -0.06420862 0.1802441 0.1372164 -0.04281044 0.1860266 0.121852 -0.06442171 0.1834348 0.1382703 -0.0429508 0.1892479 0.1228492 -0.06651419 0.1856507 0.1414791 -0.04259431 0.1922061 0.1244344 -0.06320941 0.1889215 0.1419355 -0.04176169 0.1947292 0.1265156 -0.06339859 0.1904074 0.1453121 -0.04050135 0.1966706 0.1289719 -0.06179827 0.1916572 0.1479871 -0.03888648 0.1979175 0.1316604 -0.06000822 0.1921297 0.1507889 -0.03701102 0.1983973 0.134425 -0.05807995 0.19181 0.1535234 -0.03498387 0.1980824 0.137105 -0.05033016 0.1923266 0.1521633 -0.03292292 0.1969909 0.1395446 -0.04835516 0.1905218 0.1542207 -0.03094786 0.1951861 0.141602 -0.04658085 0.188109 0.1557765 -0.02917355 0.1927733 0.1431578 -0.04511034 0.185228 0.1567401 -0.05170524 0.1797293 0.1621032 -0.05290019 0.1828765 0.1618626 -0.05441379 0.1857445 0.1609274 -0.05615806 0.1881664 0.1593519 -0.05803161 0.1900018 0.1572276 -0.07443404 0.186904 0.154471 -0.06932824 0.1887307 0.1559196 -0.07553714 0.1858028 0.151548 -0.06164193 0.1625698 0.1587128 -0.0630598 0.1613379 0.1557705 -0.07923257 0.1828066 0.1501419 -0.06485688 0.1626796 0.1632664 -0.07240897 0.1805385 0.1426383 -0.07179492 0.1774762 0.1413593 -0.05796784 0.1705967 0.1644698 -0.0707969 0.1743029 0.140789 -0.05858188 0.173659 0.1657488 -0.06947296 0.1712031 0.1409606 -0.0595799 0.1768323 0.1663191 -0.0679 0.1683571 0.1418641 -0.06090384 0.1799319 0.1661475 -0.0661695 0.16593 0.1434469 -0.06438195 0.164063 0.1456172 -0.06247681 0.1827781 0.165244 -0.06264126 0.1628647 0.1482486 -0.0640611 0.1612284 0.1524336 -0.06420737 0.1852052 0.1636612 -0.06599491 0.1870722 0.161491 -0.06773555 0.1882705 0.1588595 -0.0769394 0.1854373 0.1591784 -0.07554352 0.1848921 0.1622025 -0.0821945 0.1791194 0.1485657 -0.08190256 0.176435 0.1466034 -0.06815618 0.1632856 0.1669041 -0.08108794 0.1735152 0.1452127 -0.06907063 0.1657972 0.1691098 -0.07660853 0.1717883 0.1432774 -0.066217 0.1703553 0.1690178 -0.07515215 0.1687458 0.1433922 -0.06740599 0.1734459 0.1696699 -0.07351291 0.1659284 0.1442673 -0.06886243 0.1764883 0.169555 -0.07178622 0.1634995 0.1458518 -0.07007241 0.1616008 0.1480536 -0.07050162 0.1793058 0.1686798 -0.06847101 0.160342 0.1507447 -0.07222831 0.1817346 0.1670954 -0.07394212 0.1836334 0.1648936 -0.08546125 0.1815582 0.1584859 -0.08455848 0.1816555 0.1617365 -0.08598011 0.1807436 0.155252 -0.07173305 0.1576911 0.1622945 -0.07225197 0.1568766 0.1590605 -0.08260118 0.1688138 0.1452893 -0.07373744 0.1666225 0.1715427 -0.08100897 0.1658388 0.1453586 -0.07511204 0.169621 0.1722571 -0.07929164 0.1630601 0.1462075 -0.0767042 0.172596 0.1721878 -0.07754909 0.1606392 0.1477866 -0.07588249 0.1587169 0.1500043 -0.07842153 0.1753748 0.171339 -0.07438874 0.1574048 0.1527315 -0.07315468 0.1567793 0.1558099 -0.08016407 0.1777956 0.1697598 -0.08183068 0.1797178 0.167542 -0.08332443 0.18103 0.1648149 -0.09719049 0.1747572 0.1612352 -0.09657126 0.1746901 0.1645523 -0.0973742 0.1741369 0.1579227 -0.08201944 0.1517267 0.1647056 -0.08220314 0.1511065 0.1613931 -0.1033046 0.1689053 0.1558538 -0.1021341 0.1673315 0.1530177 -0.08806806 0.1492978 0.1687987 -0.09533435 0.1686984 0.14987 -0.08861088 0.151213 0.1714925 -0.09392267 0.1660447 0.1483352 -0.08405935 0.1571653 0.1727582 -0.09226542 0.16321 0.1475546 -0.08547097 0.159819 0.1742931 -0.09045892 0.1603593 0.1475737 -0.08712822 0.1626535 0.1750737 -0.08860808 0.1576581 0.1483912 -0.08893477 0.1655043 0.1750547 -0.08682054 0.1552633 0.1499598 -0.08520019 0.1533142 0.1521883 -0.09078556 0.1682056 0.1742371 -0.08384114 0.151924 0.1549472 -0.08282238 0.1511736 0.158076 -0.0925731 0.1706004 0.1726685 -0.09419351 0.1725495 0.17044 -0.09555256 0.1739397 0.167681 -0.1080822 0.1667945 0.1660836 -0.1071814 0.1659633 0.1692283 -0.1085242 0.1669833 0.1627431 -0.1084816 0.1665183 0.1594005 -0.09189146 0.1449553 0.166019 -0.0918489 0.1444904 0.1626763 -0.108603 0.1595569 0.1515601 -0.1039233 0.1591852 0.1496657 -0.09779363 0.1477038 0.1745092 -0.1020198 0.1565194 0.1488524 -0.09644979 0.1522884 0.1757537 -0.1000099 0.1538082 0.1488443 -0.0983532 0.1549541 0.1765671 -0.09801012 0.1512091 0.1496421 -0.1003632 0.1576654 0.1765751 -0.09613692 0.1488731 0.1511993 -0.09449899 0.1469359 0.1534255 -0.1023629 0.1602646 0.1757774 -0.09319168 0.1455103 0.1561912 -0.09229081 0.144679 0.1593358 -0.1042362 0.1626006 0.1742201 -0.1058741 0.1645377 0.171994 -0.1200391 0.1577271 0.1633612 -0.1197317 0.1574302 0.1667091 -0.1198125 0.15741 0.1600088 -0.1018901 0.136918 0.1665558 -0.1016635 0.1366009 0.1632032 -0.1190652 0.1564975 0.1568466 -0.1248187 0.1490133 0.1542769 -0.1026375 0.1378304 0.169718 -0.1103026 0.1337208 0.1727077 -0.1190682 0.146704 0.1502976 -0.1142048 0.1466902 0.1494596 -0.1122363 0.1392916 0.17642 -0.1099115 0.1458489 0.1493759 -0.1117422 0.1441557 0.177237 -0.1077512 0.1433787 0.150165 -0.1117912 0.1484791 0.1771886 -0.105771 0.1411288 0.1517165 -0.1040861 0.1392294 0.1539402 -0.1139515 0.1509492 0.1763995 -0.1027944 0.1377913 0.1567067 -0.1019709 0.1368978 0.1598554 -0.1159316 0.1531991 0.174848 -0.1176165 0.1550986 0.1726244 -0.1189082 0.1565368 0.1698578 -0.1308166 0.1475805 0.163301 -0.1305588 0.1472372 0.1666486 -0.1304939 0.147354 0.1599491 -0.1111582 0.1281926 0.166504 -0.1108355 0.127966 0.163152 -0.1296095 0.1465706 0.1567876 -0.1120427 0.128976 0.1696653 -0.12639 0.1435453 0.1517493 -0.1152621 0.1320013 0.1747037 -0.1242616 0.1323907 0.1491672 -0.1171569 0.1345238 0.1501125 -0.1271679 0.1340543 0.1769686 -0.1150395 0.132403 0.1516647 -0.1132584 0.1305943 0.1538889 -0.1244953 0.1410228 0.1763406 -0.111917 0.1292028 0.1566557 -0.1110935 0.1283094 0.1598044 -0.1266127 0.1431435 0.1747882 -0.1283939 0.1449522 0.1725641 -0.1297352 0.1463437 0.1697973 -0.1414062 0.1351719 0.1661944 -0.1405485 0.1343165 0.1693445 -0.1416497 0.1355314 0.1628473 -0.1412647 0.135374 0.159498 -0.1402738 0.1347091 0.1563411 -0.1204082 0.117904 0.1661165 -0.1200234 0.1177466 0.1627673 -0.1387343 0.1335751 0.1535599 -0.1213993 0.1185688 0.1692736 -0.1367359 0.1320379 0.1513161 -0.1229388 0.1197029 0.1720548 -0.1381453 0.1253357 0.1494952 -0.1278523 0.117413 0.1740314 -0.1365332 0.1221776 0.1486848 -0.1307174 0.1186428 0.1756499 -0.1343013 0.1194643 0.1764629 -0.1285428 0.1218959 0.1495903 -0.1265846 0.1196041 0.1510831 -0.1225468 0.120263 0.1534999 -0.1368378 0.1273323 0.1757765 -0.1211246 0.1189615 0.1562702 -0.1202669 0.1181061 0.1594203 -0.1395346 0.1288168 0.1741408 -0.1391263 0.133015 0.1721147 -0.1511 0.1221746 0.1657054 -0.1501493 0.1214439 0.1688603 -0.1513932 0.1224673 0.1623558 -0.151012 0.1223052 0.1590065 -0.1499783 0.1216975 0.1558516 -0.1285605 0.1069737 0.1657054 -0.1281792 0.1068115 0.1623558 -0.1483523 0.1206796 0.1530748 -0.1295943 0.1075814 0.1688603 -0.1462284 0.1193107 0.1508374 -0.1312203 0.1085992 0.1716371 -0.1309763 0.108961 0.1530748 -0.1294233 0.1078349 0.1558516 -0.1284725 0.1071042 0.1590065 -0.1485963 0.1203178 0.1716371 -0.1629528 0.08916741 0.1484612 -0.1654511 0.09080779 0.1500292 -0.1602254 0.0873509 0.1476536 -0.1477832 0.07847076 0.1648972 -0.1574272 0.08546376 0.1476536 -0.1474019 0.07830858 0.1615478 -0.1488169 0.07907849 0.1680521 -0.154721 0.08361577 0.1484612 -0.1504428 0.08009636 0.1708289 -0.1522639 0.08191424 0.1500292 -0.1525668 0.08146524 0.1730663 -0.1501989 0.08045816 0.1522666 -0.155065 0.08310562 0.1746343 -0.1486459 0.07933199 0.1550434 -0.1476951 0.07860136 0.1581982 -0.1577925 0.08492219 0.1754418 -0.1605907 0.08680927 0.1754418 -0.1632969 0.08865731 0.1746343 -0.1657539 0.09035879 0.1730663 -0.1678189 0.09181493 0.1708289 -0.169372 0.09294104 0.1680521 -0.1703227 0.09367173 0.1648972 -0.170616 0.09396445 0.1615478 -0.1702347 0.09380227 0.1581982 -0.169201 0.0931946 0.1550434 -0.167575 0.09217673 0.1522666 + + + + + + + + + + 0.5904216 -0.02070885 0.8068293 0.520878 0.2577078 0.8138016 0.2548883 -0.9668914 -0.01237368 0.6061244 -0.2068121 0.7680118 0.5779619 0.02340048 0.8157282 0.1149837 -0.9711856 -0.2087522 0.598176 -0.4468477 0.6652163 0.2575997 -0.9662262 -0.007039725 0.6067323 -0.2107997 0.7664461 -0.0316472 -0.9189704 -0.3930549 0.5601235 -0.6219342 0.5472291 0.1179968 -0.9719402 -0.2034918 0.5984462 -0.4332463 0.6739138 -0.1761186 -0.813583 -0.5541346 0.4845856 -0.7894935 0.3766656 -0.02849811 -0.9211769 -0.3880993 0.5586057 -0.6296672 0.539888 0.3807736 -0.9056075 0.1867797 0.4843279 -0.7900133 0.3759065 -0.3101558 -0.6613435 -0.6829555 -0.1733133 -0.8168754 -0.5501611 0.3821304 -0.9043869 0.1898966 -0.4261421 -0.4710891 -0.7723199 -0.3080118 -0.6651142 -0.6802586 -0.5175209 -0.25367 -0.8172049 -0.4247968 -0.4746516 -0.7708784 -0.5790452 -0.02145045 -0.8150132 -0.5168477 -0.2566043 -0.8167147 -0.6071632 0.2123619 -0.7656732 -0.5788519 -0.02366405 -0.8150894 -0.6019536 0.4173889 -0.6807631 -0.6072512 0.2106645 -0.7660722 -0.5557323 0.6361655 -0.535215 -0.5987648 0.4331635 -0.673684 -0.5586369 0.6296614 -0.5398625 -0.4837736 0.7907555 -0.3750585 -0.4843415 0.7900102 -0.3758955 -0.3841285 0.9030688 -0.1921253 -0.3823266 0.9043285 -0.1897797 -0.2609659 0.9653401 0.003924071 -0.1225546 0.9720827 0.200089 -0.2580592 0.9661011 0.007377922 4.78516e-4 0.9339252 0.3574685 -0.1188193 0.9717163 0.2040821 0.1774641 0.8179937 0.5471681 0.03224664 0.922205 0.3853548 0.3123281 0.6662771 0.6771454 0.177455 0.8180025 0.5471579 0.4290789 0.4758051 0.7677897 0.3123474 0.6662693 0.6771442 0.5208849 0.2576811 0.8138055 0.4290854 0.4758037 0.7677869 0.4794657 0.2464388 0.8422475 0.5367603 0.05581808 0.8418865 0.3849585 0.4634226 0.7981519 0.4794629 0.2464228 0.8422537 0.2681592 0.6535416 0.7077952 0.3849595 0.4634383 0.7981424 0.2681547 0.653555 0.7077846 0.1358119 0.8057961 0.5764094 0.135819 0.8057798 0.5764307 0.01704078 0.8986062 0.438425 -0.3422234 0.9393681 0.02170163 -0.320301 0.9462442 0.04504704 -0.4260512 0.8878641 -0.1737183 -0.420421 0.8921422 -0.1653133 0.4232574 -0.8901569 0.168742 -0.4924752 0.7843943 -0.3770862 -0.490626 0.7870995 -0.3738454 0.4180482 -0.8939179 0.1616991 -0.5321643 0.6183601 -0.578301 0.4890002 -0.7925373 0.3643673 0.4893532 -0.7890035 0.3714929 -0.5485242 0.4767423 -0.6869047 0.5273134 -0.6549034 0.5413337 -0.5303606 0.2339786 -0.8148446 -0.5303936 0.2337428 -0.8148909 0.547678 -0.4104772 0.7290798 -0.4813275 0.006148636 -0.8765194 -0.4812792 0.007120907 -0.8765385 0.530465 -0.2339368 0.8147887 0.5305838 -0.234198 0.8146362 -0.4043869 -0.2218412 -0.8872755 -0.4044665 -0.2199542 -0.8877089 0.4745272 -0.008948802 0.8801954 0.4868912 -0.02724885 0.8730375 -0.3040796 -0.4368155 -0.8465978 -0.3044019 -0.4342892 -0.8477809 0.3967648 0.2188155 0.8914582 0.3967651 0.2188041 0.8914607 -0.1861833 -0.6263871 -0.7569512 -0.1867479 -0.623782 -0.7589606 -0.0574547 -0.7797446 -0.623456 -0.05816817 -0.7774846 -0.6262063 0.2960234 0.4337559 0.8510147 0.2960388 0.4337366 0.8510193 0.07469791 -0.8879734 -0.4537882 0.07399302 -0.8864496 -0.4568722 0.1948183 -0.9341089 -0.2991431 0.2021725 -0.9441062 -0.2603646 0.1781755 0.6234866 0.7612609 0.3225001 -0.9442818 -0.0657702 0.1781567 0.623494 0.7612592 0.3253337 -0.9442226 -0.05100643 0.04996418 0.777125 0.6273599 0.04998993 0.7771142 0.6273713 -0.09461498 0.8941345 0.437689 -0.0747258 0.8879749 0.4537805 -0.2052934 0.9448278 0.2552551 -0.202683 0.9447299 0.2576918 -0.2722463 0.9171634 0.2910212 -0.3596957 0.9279404 0.09770154 -0.5205759 0.6532118 -0.5498319 -0.505715 0.4725964 -0.7217376 -0.5135691 0.4229041 -0.7465916 0.5225048 -0.6265796 0.5782619 -0.4651199 0.2715489 -0.8425703 -0.465668 0.2599335 -0.8459243 0.5041345 -0.4589399 0.7315891 0.5207412 -0.4938015 0.6964113 -0.3951949 0.004340171 -0.918587 -0.397179 0.03986757 -0.9168748 0.4783012 -0.2826574 0.8314642 0.4658347 -0.2598742 0.8458508 -0.3172028 -0.1869251 -0.9297534 -0.3172039 -0.1869523 -0.9297476 0.4065378 -0.03621333 0.9129161 0.4065416 -0.03620988 0.9129145 -0.2094822 -0.3991359 -0.8926409 -0.2094851 -0.3991443 -0.8926364 0.3171821 0.1869492 0.9297557 0.3171907 0.1869485 0.9297529 -0.08967 -0.5881218 -0.803786 -0.08967012 -0.5881168 -0.8037897 0.03536462 -0.7430426 -0.6683092 0.03536552 -0.7430297 -0.6683234 0.2094842 0.3991399 0.8926387 0.2094811 0.3991424 0.8926383 0.1583585 -0.8548691 -0.4940865 0.1583651 -0.854882 -0.4940622 0.2859832 -0.9213711 -0.2632279 0.0896703 0.588122 0.803786 0.08967387 0.5881159 0.80379 -0.03535515 0.7430222 0.6683323 -0.03537762 0.7430359 0.668316 -0.1583841 0.8548849 0.494051 -0.158352 0.854873 0.494082 -0.2722311 0.9171592 0.2910488 -0.4186384 0.9037597 0.08922052 -0.335106 0.8880414 0.31478 -0.4734096 0.869166 -0.142947 -0.4175949 0.9066343 0.06023967 0.4731068 -0.8693168 0.1430326 -0.5060265 0.7883517 -0.3499127 -0.4733127 0.8682833 -0.1485237 0.5082281 -0.7740796 0.3774983 0.4704239 -0.8715479 0.1382237 -0.2451729 -0.153519 -0.9572473 -0.3614317 0.1012299 -0.9268872 0.3461614 -0.06430596 0.9359685 0.4145768 -0.241837 0.8772919 -0.1300302 -0.3623226 -0.922938 -0.2452052 -0.1534932 -0.9572431 0.2451894 0.1535143 0.9572438 0.346157 -0.06430846 0.93597 -0.007375419 -0.5500342 -0.8351096 -0.1300382 -0.362325 -0.9229359 0.1157408 -0.7058674 -0.6988243 -0.007357239 -0.5500398 -0.835106 0.1300413 0.3622994 0.9229456 0.2451862 0.1535177 0.957244 0.2321245 -0.8207552 -0.5219954 0.1157399 -0.7058675 -0.6988244 0.3350973 -0.8880465 -0.3147753 0.2321177 -0.820743 -0.5220174 0.007357716 0.550065 0.8350895 0.4115144 -0.9072292 -0.08712697 0.130039 0.3623271 0.922935 0.3086171 -0.8885056 -0.3395783 0.4077625 -0.9083874 -0.09253233 0.007361531 0.5500411 0.8351052 -0.1157352 0.7058706 0.698822 -0.1157371 0.7058732 0.698819 -0.2321184 0.8207417 0.5220193 -0.2321184 0.8207463 0.5220121 -0.3350996 0.888045 0.3147764 -0.4798032 0.8708038 0.107191 -0.4118589 0.8465942 0.3371211 -0.5199022 0.8443883 -0.129269 -0.4797986 0.8708083 0.1071744 0.5199103 -0.8443853 0.1292548 -0.5285627 0.7536486 -0.3906857 -0.5199003 0.8443934 -0.1292423 -0.5279918 0.7526746 -0.3933263 -0.5083795 0.6466725 -0.5686519 0.530257 -0.7863655 0.3169493 0.519902 -0.8443908 0.1292521 -0.4469606 0.4681628 -0.7622663 -0.51015 0.6503769 -0.5628117 0.5091226 -0.6497144 0.5645047 0.5292383 -0.7898638 0.3098742 -0.3850501 0.2999803 -0.8727819 -0.4620488 0.4900742 -0.7391469 0.4629384 -0.5083884 0.7261056 0.5088703 -0.6458771 0.5691168 -0.2870258 0.09469383 -0.953231 -0.3891766 0.3053682 -0.8690753 0.3851535 -0.2999143 0.8727591 0.4603799 -0.4852217 0.7433776 -0.1651979 -0.1112458 -0.9799664 -0.2659002 0.06992167 -0.9614614 0.2809553 -0.09863007 0.9546393 0.3909455 -0.3263227 0.8606247 -0.03998833 -0.3144367 -0.9484359 -0.1652013 -0.1112454 -0.9799658 0.1652119 0.1112234 0.9799666 0.280968 -0.0986436 0.9546343 0.08748096 -0.4993129 -0.8619941 -0.03997737 -0.3144547 -0.9484303 0.2098374 -0.6552504 -0.7256826 0.08746457 -0.4993112 -0.8619968 0.0399847 0.3144531 0.9484307 0.1652051 0.111239 0.9799659 0.3200821 -0.7732875 -0.5473335 0.2098484 -0.6552591 -0.7256716 0.4118516 -0.8465884 -0.3371446 0.3200868 -0.7732867 -0.547332 -0.08747953 0.4993123 0.8619945 0.4798024 -0.8708055 -0.1071794 0.03999376 0.3144305 0.9484376 0.4118656 -0.8465891 -0.3371257 0.4798012 -0.870805 -0.1071894 -0.08748453 0.4993405 0.8619776 -0.2098394 0.655257 0.725676 -0.2098405 0.655262 0.7256712 -0.3200829 0.7732863 0.5473347 -0.320079 0.7732794 0.5473467 -0.411855 0.8465867 0.3371446 -0.497128 0.7930499 0.3520448 -0.550719 0.8260881 0.119529 -0.5507221 0.8260875 0.1195187 -0.5723623 0.8111527 -0.1201365 -0.5723638 0.8111535 -0.1201236 -0.5653718 0.7639089 -0.311124 0.5723651 -0.811154 0.1201139 0.5723613 -0.8111556 0.1201215 0.5563043 -0.7363389 0.3851374 -0.4438588 0.5077424 -0.7383679 -0.3344644 0.3153684 -0.8880745 -0.3391162 0.3293027 -0.8812264 0.435824 -0.4933279 0.7527849 -0.2218557 0.1361581 -0.9655264 -0.2218623 0.1361776 -0.9655221 0.349016 -0.3394074 0.8734933 0.3391803 -0.3292662 0.8812154 -0.0890125 -0.06302249 -0.9940348 -0.08900284 -0.06305456 -0.9940336 0.2218728 -0.1361904 0.9655179 0.2218571 -0.1361812 0.9655228 0.04894268 -0.2584832 -0.9647752 0.04892557 -0.2584609 -0.9647821 0.08900028 0.06305003 0.9940341 0.08900928 0.06303203 0.9940344 0.1839527 -0.4388011 -0.8795539 0.1839599 -0.4387992 -0.8795533 0.3082784 -0.5936256 -0.7433527 0.3082796 -0.5936275 -0.7433506 -0.0489133 0.258454 0.9647845 -0.04894542 0.2584759 0.964777 0.4147018 -0.7140137 -0.5640984 0.4147089 -0.7140269 -0.5640766 0.497122 -0.7930466 -0.3520607 0.4971311 -0.79304 -0.352063 -0.1839724 0.4388159 0.8795424 0.5507248 -0.826089 -0.1194955 -0.1839613 0.4387999 0.8795527 0.5507231 -0.8260865 -0.1195213 -0.3082792 0.5936205 0.7433564 -0.3082736 0.5936167 0.7433617 -0.4147075 0.7140258 0.5640789 -0.4147083 0.7140275 0.5640761 -0.497124 0.7930431 0.3520658 -0.6174609 0.7765155 0.1255625 -0.5729973 0.7367929 0.3589016 -0.626096 0.7711793 -0.1152672 -0.6174585 0.776517 0.1255648 0.6261023 -0.771175 0.1152613 -0.5983436 0.7210152 -0.3494599 -0.6260958 0.7711797 -0.1152644 -0.5877569 0.716515 -0.3756971 -0.5140365 0.6042139 -0.6088449 0.5983397 -0.7210071 0.3494832 0.6260964 -0.7711841 0.1152325 -0.4568983 0.5160036 -0.7245581 -0.5359841 0.6247093 -0.5678552 0.5524608 -0.661228 0.5075085 0.5977165 -0.733461 0.3236823 0.4348791 -0.4866487 0.757663 0.5399123 -0.6308237 0.5572758 -0.1673634 0.1537833 -0.9738276 -0.3269932 0.3523777 -0.8768725 -0.02540755 -0.03023439 -0.99922 -0.181995 0.1657452 -0.9692298 0.1900528 -0.1813755 0.9648745 0.3116586 -0.3329261 0.8899603 0.115813 -0.2089275 -0.9710492 -0.03510892 -0.02304869 -0.9991177 0.04059338 0.01165169 0.9991078 0.1821311 -0.1656954 0.9692128 0.259943 -0.3825823 -0.8866006 0.1158238 -0.2089422 -0.9710449 0.3889089 -0.5339568 -0.7507596 0.2599419 -0.3825765 -0.8866033 -0.1158114 0.2089261 0.9710499 0.03509068 0.02307188 0.9991178 0.4953127 -0.6543384 -0.5714077 0.3889207 -0.533957 -0.7507535 0.5729869 -0.73679 -0.3589243 0.4952952 -0.6543275 -0.5714352 -0.2599514 0.3825872 0.8865959 0.6174532 -0.7765216 -0.1255626 -0.1158125 0.2089182 0.9710514 0.5729948 -0.7367848 -0.3589223 0.6174679 -0.776515 -0.1255304 -0.2599481 0.3825924 0.8865947 -0.3889049 0.533945 0.7507702 -0.3889053 0.5339431 0.7507713 -0.4953109 0.6543393 0.5714082 -0.4953048 0.6543371 0.571416 -0.5730004 0.7367829 0.3589173 -0.6803361 0.7219108 0.1264425 -0.6405748 0.6782845 0.3599919 -0.6806285 0.7236379 -0.114425 -0.6803411 0.7218977 0.1264896 0.6806246 -0.7236381 0.1144476 -0.6413891 0.6833546 -0.3487788 -0.6806232 0.7236378 -0.1144562 -0.6413919 0.683358 -0.3487671 -0.5876655 0.6272513 -0.5110823 0.6413957 -0.6833487 0.3487781 0.6806201 -0.7236413 0.1144539 0.5471192 -0.5847057 0.5989824 0.641387 -0.6833519 0.3487877 -0.3256117 0.3513447 -0.8778007 -0.4382477 0.4778557 -0.7613101 0.3149368 -0.3393833 0.8863598 0.4674943 -0.5111333 0.7212433 0.1825563 -0.1796611 -0.9666411 -0.01361173 0.03000479 -0.9994571 0.3179306 -0.3324412 -0.8879207 0.1633434 -0.1677328 -0.9722062 0.4540006 -0.4777715 -0.7520758 0.3179426 -0.3324455 -0.8879147 -0.1509572 0.1460083 0.977698 -0.02454388 0.01091939 0.9996391 0.5636396 -0.5952974 -0.5726531 0.4539867 -0.4777718 -0.752084 0.6405797 -0.6782798 -0.359992 0.5636569 -0.5953063 -0.5726268 -0.3179506 0.3324561 0.8879079 0.6803384 -0.7219002 -0.1264903 -0.1633397 0.1677314 0.972207 0.6405751 -0.6782758 -0.3600076 0.6803318 -0.7219071 -0.1264867 -0.3179438 0.3324518 0.8879119 -0.453994 0.4777626 0.7520854 -0.4539828 0.4777536 0.7520978 -0.5636518 0.5953128 0.5726252 -0.5636581 0.5953058 0.5726261 -0.6405689 0.6782712 0.3600274 -0.700932 0.6166909 0.3583108 -0.7401534 0.660752 0.1248189 -0.7401663 0.6607457 0.1247764 -0.7364505 0.66648 -0.1159533 -0.7364479 0.6664866 -0.1159318 -0.6900081 0.633539 -0.3500249 -0.6900039 0.6335355 -0.3500394 0.7364482 -0.666482 0.1159568 0.7364513 -0.6664789 0.1159538 -0.6003654 0.5673276 -0.5636496 -0.5901753 0.5527588 -0.5883459 0.6900116 -0.6335327 0.3500292 0.6900032 -0.6335375 0.3500372 -0.4818021 0.4612234 -0.7450771 -0.4925944 0.4777894 -0.7273706 0.6003066 -0.5673931 0.5636464 0.6146354 -0.5730062 0.5421138 -0.3085798 0.3092793 -0.8995137 -0.3137844 0.3158147 -0.8954331 0.5095658 -0.4728937 0.7188284 0.4635704 -0.4533394 0.7613055 -0.1540359 0.1710724 -0.9731431 -0.1663787 0.1849067 -0.9685699 0.3463171 -0.3425347 0.8733468 0.3641062 -0.3539344 0.8614855 0.05366188 -0.01732718 -0.9984089 0.1754237 -0.1905586 0.9658747 0.1598804 -0.1792919 0.9707176 0.1622787 -0.1057564 -0.9810613 0.007779181 -0.038437 0.9992308 0.3541169 -0.2788639 -0.8926568 0.360893 -0.288729 -0.8867874 0.513759 -0.4340385 -0.7400421 0.5072642 -0.4234684 -0.7505716 -0.2417849 0.178682 0.9537363 0.6210411 -0.5368611 -0.5710413 0.6210322 -0.5368354 -0.571075 0.7009312 -0.6166919 -0.3583108 0.7009311 -0.616697 -0.3583022 -0.3714305 0.2952246 0.8802737 0.740157 -0.6607486 -0.1248151 -0.3608528 0.2887939 0.8867827 0.7401552 -0.6607491 -0.1248242 -0.5071883 0.4235301 0.750588 -0.4949141 0.4162532 0.7627537 -0.621039 0.536857 0.5710474 -0.6210347 0.5368494 0.5710593 -0.700918 0.6166933 0.3583343 -0.755689 0.5502535 0.3551834 -0.7978515 0.5904958 0.1214408 -0.7978473 0.5904958 0.1214672 -0.7937276 0.5964751 -0.1192228 -0.7937254 0.5964732 -0.1192475 -0.7435747 0.5678681 -0.3530191 -0.7435789 0.5678686 -0.3530094 0.7937259 -0.5964742 0.1192384 0.7937252 -0.5964739 0.1192445 -0.6502772 0.5063126 -0.5663809 -0.6502775 0.5063016 -0.5663903 0.7435678 -0.5678673 0.3530348 0.7435779 -0.5678672 0.3530139 -0.5191895 0.4153264 -0.746958 -0.519203 0.4153386 -0.7469418 0.6502901 -0.5063119 0.5663664 0.6502719 -0.5063087 0.5663903 -0.3799586 0.3160834 -0.8693232 0.4961742 -0.3990648 0.7710763 0.5216876 -0.3600025 -0.77346 0.6696316 -0.4780539 -0.5683821 0.6696346 -0.4780661 -0.5683681 0.7556791 -0.550262 -0.3551915 0.7556896 -0.5502593 -0.3551732 0.7978453 -0.590498 -0.1214708 0.7978514 -0.5904906 -0.1214669 -0.5732832 0.4006845 0.7147015 -0.6696285 0.4780521 0.5683871 -0.6696336 0.4780563 0.5683776 -0.755689 0.5502564 0.355179 -0.34538 0.2626555 -0.9009577 -0.3736572 0.2770983 -0.8852101 -0.1849938 0.1545901 -0.9705047 -0.1845757 0.1543418 -0.9706238 0.8214462 -0.5574104 0.1204979 0.03025019 0.01085412 -0.9994835 0.8214458 -0.5574089 0.1205081 0.01368123 0.02029019 -0.9997006 0.7705326 -0.5297108 0.3545226 0.2429562 -0.1378253 -0.960196 0.7705422 -0.5297128 0.3544985 0.2097851 -0.1169568 -0.9707273 0.6748581 -0.471231 0.5678979 0.3924403 -0.2425742 -0.8872138 0.6748536 -0.4712274 0.5679062 0.3956622 -0.2444627 -0.8852624 0.5701764 -0.4110955 0.7112661 0.5887075 -0.3767511 -0.7151799 0.5399275 -0.3853584 0.7483163 0.5576739 -0.3590385 -0.7483924 0.3766519 -0.2832576 0.8819856 0.6897831 -0.4490926 -0.5679042 0.3720307 -0.2795405 0.8851273 0.6897798 -0.449092 -0.5679088 0.7798564 -0.5158913 -0.3545141 0.77986 -0.5158933 -0.3545033 0.1847888 -0.1543639 0.9705797 0.8246115 -0.5527147 -0.1205094 0.1846169 -0.1542237 0.9706347 0.8246177 -0.5527099 -0.1204889 0.01070648 -0.03986531 0.9991477 -0.01365661 -0.02026063 0.9997015 -0.1912621 0.1020195 0.9762228 -0.2097253 0.1169971 0.9707354 -0.3992267 0.2475129 0.8828111 -0.3956367 0.2445296 0.8852552 -0.5295495 0.3350417 0.7793102 -0.5575715 0.35922 0.7483817 -0.6897736 0.4490808 0.5679252 -0.6897801 0.4490987 0.5679031 -0.7798622 0.5159033 0.3544839 -0.7798604 0.5158892 0.3545085 -0.8246147 0.5527085 0.1205161 -0.8246152 0.552714 0.1204864 -0.8214487 0.5574083 -0.1204912 -0.8214403 0.5574175 -0.1205062 -0.770542 0.5297118 -0.3545003 -0.7705388 0.5297163 -0.3545006 -0.6748502 0.4712302 -0.5679078 -0.6748473 0.4712324 -0.5679095 -0.5399273 0.3853563 -0.7483176 -0.5399352 0.3853546 -0.7483127 0.7912328 0.2120075 -0.5735883 0.791236 0.2120152 -0.5735812 0.7912414 0.2120013 -0.5735786 0.7912501 0.2119692 -0.5735787 0.7913165 0.2120231 -0.573467 0.7912563 0.2120027 -0.5735577 0.7912518 0.211986 -0.5735701 0.791235 0.2120158 -0.5735822 0.7912204 0.2120236 -0.5735995 0.7912799 0.2120056 -0.5735239 0.791236 0.2120193 -0.5735794 0.7912395 0.2120092 -0.5735784 0.7912396 0.2120127 -0.573577 0.7912386 0.2120166 -0.5735769 0.7912441 0.2120113 -0.5735713 0.7912348 0.2120252 -0.573579 0.7912338 0.2120116 -0.5735852 0.7912432 0.2120312 -0.5735651 0.791219 0.2119664 -0.5736225 0.7912322 0.2120044 -0.5735902 0.7912422 0.2120044 -0.5735765 0.7912436 0.2120052 -0.5735741 0.7912406 0.212011 -0.5735762 0.7912418 0.2120156 -0.5735729 -0.5590085 -0.8288297 -0.02347469 -0.5589939 -0.8288384 -0.02351206 -0.5590159 -0.8288242 -0.0234875 -0.5589736 -0.8288509 -0.0235539 -0.5589802 -0.8288479 -0.02350223 -0.5589868 -0.8288434 -0.02350336 -0.5589742 -0.8288524 -0.0234853 -0.5590426 -0.8288044 -0.02355504 -0.5589831 -0.8288457 -0.0235086 -0.558952 -0.8288679 -0.02346533 -0.5589609 -0.8288612 -0.02349323 -0.5589901 -0.8288416 -0.02348923 -0.5589735 -0.8288522 -0.02350759 -0.5589836 -0.8288456 -0.02350246 -0.5589842 -0.8288453 -0.02350211 -0.5589789 -0.8288491 -0.02349358 -0.5590326 -0.8288125 -0.02350598 -0.5589383 -0.828876 -0.02350819 -0.5589696 -0.8288552 -0.02350127 -0.5589739 -0.8288511 -0.02353793 -0.5589843 -0.8288447 -0.02351713 -0.5589814 -0.8288471 -0.02350312 -0.5589717 -0.8288536 -0.02350455 -0.5589785 -0.8288486 -0.02351939 + + + + + + + + + + + + + + +

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

+
+
+
+ + + + -0.03999996 -0.04999995 0.1019999 -0.05603414 -0.05603414 0.1019999 -0.04999995 -0.03999996 0.1019999 0.04999995 0.03999996 0.1019999 0.03999996 0.04999995 0.1019999 0.05603414 0.05603414 0.1019999 0.05918055 0.03999996 0.1019999 0.06410998 0.04657858 0.1019999 -0.03999996 -0.05918055 0.1019999 -0.04657858 -0.06410998 0.1019999 0.06318056 0.03599995 0.1019999 -0.06318056 0.03599995 0.1019999 -0.07536578 0.02448779 0.1019999 -0.07060712 0.03597611 0.1019999 -0.06410998 0.04657858 0.1019999 -0.03599995 -0.06318056 0.1019999 0.07060712 0.03597611 0.1019999 -0.05918055 0.03999996 0.1019999 -0.05603414 0.05603414 0.1019999 -0.03597611 -0.07060712 0.1019999 -0.03599995 0.06318056 0.1019999 -0.04657858 0.06410998 0.1019999 -0.03597611 0.07060712 0.1019999 -0.02448779 0.07536578 0.1019999 0.07536578 0.02448779 0.1019999 -0.03999996 0.05918055 0.1019999 -0.02448779 -0.07536578 0.1019999 0.07826864 0.01239651 0.1019999 -0.01239651 0.07826864 0.1019999 -0.01239651 -0.07826864 0.1019999 -0.07826864 0.01239651 0.1019999 -0.04999995 0.03999996 0.1019999 -0.03999996 0.04999995 0.1019999 0.07536578 -0.02448779 0.1019999 0.06318056 -0.03599995 0.1019999 0.07826864 -0.01239651 0.1019999 0.02448779 -0.07536578 0.1019999 0.01239651 -0.07826864 0.1019999 0.03599995 -0.06318056 0.1019999 0.07060712 -0.03597611 0.1019999 0.03599995 0.06318056 0.1019999 0.01239651 0.07826864 0.1019999 0.02448779 0.07536578 0.1019999 0.03597611 0.07060712 0.1019999 0.03597611 -0.07060712 0.1019999 0.04657858 -0.06410998 0.1019999 0.03999996 -0.05918055 0.1019999 -0.06318056 -0.03599995 0.1019999 -0.07060712 -0.03597611 0.1019999 -0.07536578 -0.02448779 0.1019999 -0.07826864 -0.01239651 0.1019999 0.06410998 -0.04657858 0.1019999 0.05918055 -0.03999996 0.1019999 0.05603414 -0.05603414 0.1019999 0.03999996 -0.04999995 0.1019999 0.04999995 -0.03999996 0.1019999 0.04657858 0.06410998 0.1019999 0.03999996 0.05918055 0.1019999 0 -0.07924425 0.1019999 0.07924425 0 0.1019999 -0.06410998 -0.04657858 0.1019999 -0.05918055 -0.03999996 0.1019999 0 0.07924425 0.1019999 -0.07924425 0 0.1019999 0.07532221 0.0246461 -0.06827837 0.07827591 0.01234835 -0.07252287 0.07924425 0 -0.07386839 0.07826864 -0.01239651 -0.07276403 0.07550746 -0.02401578 -0.06964313 0.07068169 -0.0358197 -0.06391465 0.06409913 -0.04659456 -0.05595767 0.05603414 -0.05603414 -0.04622715 0.04657858 -0.06410998 -0.03521597 0.03588598 -0.07065862 -0.02369081 0.02448779 -0.07536578 -0.01267004 0.01239651 -0.07826864 -0.002447247 -2.99303e-5 -0.07924735 0.006598949 -0.01239651 -0.07826864 0.01448237 -0.02448779 -0.07536578 0.02114892 -0.035869 -0.07065969 0.02663975 -0.04657858 -0.06410998 0.0312829 -0.05603414 -0.05603414 0.03495746 -0.06410998 -0.04657858 0.03783315 -0.07060712 -0.03597611 0.03998947 -0.07533371 -0.02459615 0.04141277 -0.07826864 -0.01239651 0.04237824 -0.07924425 0 0.04267305 -0.07826864 0.01239651 0.0423879 -0.07536578 0.02448779 0.04153341 -0.07060712 0.03597611 0.04009962 -0.06410998 0.04657858 0.03805935 -0.05596989 0.05609655 0.03532582 -0.04657858 0.06410998 0.03197216 -0.03597611 0.07060712 0.02780407 -0.02448779 0.07536578 0.02279102 -0.01216727 0.07830303 0.01667624 0 0.07924425 0.009907364 0.01239651 0.07826864 0.001875579 0.0245518 0.07534462 -0.007375895 0.03597611 0.07060712 -0.01759284 0.04657858 0.06410998 -0.02882891 0.05601447 0.05605912 -0.04052335 0.06410998 0.04657858 -0.05170387 0.07045447 0.03630232 -0.06106454 -0.03999996 -0.05918055 0.104 -0.03599995 -0.06318056 0.104 0.03599995 -0.06318056 0.104 0.03999996 -0.05918055 0.104 0.03999996 -0.04999995 0.104 0.04999995 -0.03999996 0.104 0.05918055 -0.03999996 0.104 0.06318056 -0.03599995 0.104 0.06318056 0.03599995 0.104 0.05918055 0.03999996 0.104 0.04999995 0.03999996 0.104 0.03999996 0.04999995 0.104 0.03999996 0.05918055 0.104 0.03599995 0.06318056 0.104 -0.03599995 0.06318056 0.104 -0.03999996 0.05918055 0.104 -0.03999996 0.04999995 0.104 -0.04999995 0.03999996 0.104 -0.05918055 0.03999996 0.104 -0.06318056 0.03599995 0.104 -0.06318056 -0.03599995 0.104 -0.05918055 -0.03999996 0.104 -0.04999995 -0.03999996 0.104 -0.03999996 -0.04999995 0.104 0.06182599 0.05978912 -0.03880625 0.06651234 0.06200122 -0.0375905 0.09446388 0.04839408 -0.06112807 0.1436639 0.01557385 -0.09983259 0.1210362 0.01583427 -0.09066712 0.1056694 0.0113191 -0.08478057 -0.02484762 0.1174546 0.104223 -0.0211507 0.1148565 0.08884984 -0.034491 0.1143035 0.1038165 0.1075448 0.01721578 -0.08460581 -0.03067803 0.1115049 0.0881952 -0.06897401 0.04766988 0.04432594 -0.06209558 0.0602706 0.04520118 0.08274298 0.04814022 -0.0576213 0.09223318 0.04259896 -0.06601053 -0.02895104 0.1102401 0.08255571 0.08954483 0.04071152 -0.06642264 -0.05561637 0.06721806 0.043971 -0.05642944 0.0604403 0.03911882 -0.06768774 0.07125651 0.06222099 -0.06201249 0.07797902 0.0627762 -0.05168151 0.07404094 0.04649937 0.07752203 0.02820652 -0.06801241 0.08331471 0.03135424 -0.0692591 0.1106973 0.02463972 -0.08406853 -0.05597382 0.09484452 0.08055377 -0.0457428 0.1018189 0.08130109 -0.03831267 0.0978229 0.06500053 0.1087081 0.02041733 -0.08439201 -0.04796379 0.09098893 0.06410348 -0.01781225 0.1142811 0.08361023 0.09713226 0.04357916 -0.06696301 0.08442449 0.03353339 -0.06868624 -0.09151268 0 0.05896425 -0.008726894 0.1178547 0.0891124 0.08960568 0.03570014 -0.06973373 0.1116554 0.02783721 -0.08335977 -0.04294419 0.08119034 0.04550039 -0.0539304 0.08599019 0.06354528 -0.04455387 0.07085156 0.03601235 0.1057794 0.04182171 -0.07190793 0.1230196 0.02365726 -0.08993089 -0.03597593 0.1070812 0.08204424 -0.0292142 0.1029356 0.06584036 0.004017353 0.1195838 0.08926367 0.008041799 0.1158386 0.07316833 -0.007455766 0.1168128 0.08420377 -0.03744566 0.0859639 0.04616725 0.113398 0.03061878 -0.08298528 -0.02255451 0.106089 0.06645315 -0.03128433 0.09188801 0.0488156 0.1144353 0.03315484 -0.08220601 -0.01211267 0.1100567 0.06744748 0.1444408 0.03099995 -0.09769809 0.1244046 0.02708762 -0.08961218 -0.02748602 0.09435546 0.04925495 0.1167829 0.03648924 -0.08130782 0.1265756 0.03303176 -0.08852064 0.115419 0.03471279 -0.08177965 0.1351591 0.03137224 -0.0936467 0.1255659 0.02939629 -0.08942365 -0.03305757 0.07641816 0.03100615 -0.025855 0.09096705 0.04279822 0.1257596 0.03119152 -0.08884811 -0.02011239 0.09744298 0.04819107 -0.002442121 0.1127112 0.06837081 0.0136221 0.1108058 0.05687409 -0.02712458 0.08107191 0.0311262 -0.01493948 0.1010696 0.05066865 -0.02050977 0.08587342 0.03172463 -0.005178034 0.1049833 0.05179399 -0.01179033 0.09890538 0.04471731 -0.120934 0 0.1212438 -0.1193527 0.01976478 0.1212393 -0.1144888 0.03911435 0.1212363 -0.1136519 0 0.09789121 -0.0172069 0.08858335 0.03282612 -0.1128712 0.04323971 0.1207313 -0.1076577 0.05527383 0.121246 -0.1126305 0.01923698 0.09926468 -0.108155 0.03797584 0.0997495 -0.0989629 0.07058954 0.123634 -0.09187579 0.07975661 0.1236584 -0.09861707 0.0703575 0.1212523 -0.1067625 0.04200267 0.0998665 -0.01134121 0.09207993 0.03363263 -0.1026836 0 0.07602524 -0.1048535 0.01864719 0.08245539 -0.08477294 0.08733445 0.1236708 -0.002162516 0.1026343 0.04551136 0.004611611 0.1072353 0.05152118 0.01272946 0.1089333 0.05246162 -0.1011717 0.05488359 0.1002769 -0.00578922 0.09518307 0.03475916 -0.1014603 0.01840162 0.076478 -0.1006509 0.03681707 0.0830186 -0.09933674 0.0407238 0.08315849 -0.06773549 0.1013634 0.1237233 -0.07472932 0.09578514 0.1219056 -0.09256392 0.06931823 0.1007348 0.001787662 0.0982089 0.03547668 -0.09689915 0.03790003 0.07706397 0.005742669 0.09938532 0.03558504 -0.007494866 0.08293008 0.01891535 -0.05833935 0.1072111 0.1237569 0.01099103 0.1017557 0.03771889 -0.08623468 0.07761871 0.1011754 -6.59318e-4 0.08588224 0.01840156 0.009298622 0.09297728 0.02334094 -0.09404808 0.05322921 0.08365809 -0.09043139 0.01760017 0.05945158 0.002277553 0.09001517 0.02243596 -0.07971584 0.08484476 0.101527 -0.09090989 0.05253738 0.07773047 0.005844235 0.08800661 0.01769983 -0.04757368 0.1126242 0.1238102 -0.05334466 0.1096404 0.1224246 0.01383471 0.09159618 0.01914346 -0.08594137 0.06722879 0.08431309 0.02141177 0.09402197 0.02023833 0.03048634 0.09626328 0.02185934 0.01733863 0.08095824 0.002740621 -0.03770881 0.1165276 0.1238602 -0.07044935 0.09339642 0.1020053 -0.08621537 0.03626894 0.06012201 0.02434033 0.08427923 0.004204034 -0.0829885 0.06633269 0.07840347 0.03115224 0.08673864 0.005574345 0.0421797 0.08660179 0.002870142 -0.07987433 0.07535672 0.08478879 0.0319522 0.07934021 -0.005318105 0.03833764 0.08149099 -0.004280924 -0.06361871 0.09868645 0.1023471 0.05487036 0.07674962 -0.01480746 0.04317343 0.07214587 -0.01836717 -0.02723085 0.1196504 0.1239268 0.0482912 0.0744 -0.01689636 -0.07367801 0.08241474 0.08524149 -0.07704138 0.07440274 0.07892644 0.0807501 0.01747024 -0.07269865 -0.02080589 0.1187885 0.1058059 -0.05260223 0.105834 0.1029153 0.1081461 0.002743721 -0.08652204 -0.08064109 0.05027091 0.06085312 -0.02270019 0.1206315 0.1231312 -0.01364892 0.122341 0.1240259 0.08213013 0.02232307 -0.07208704 -0.07097524 0.08138543 0.0794081 -0.0648626 0.09079408 0.08586448 0.001458585 0.1220956 0.1055166 1.77445e-4 0.1235482 0.1241413 -0.0740745 0.03234839 0.04268771 -0.04219979 0.1110766 0.1033885 -0.073237 0.06352627 0.06163942 0.1434038 0 -0.1005471 0.119345 0.006335973 -0.09097164 -0.05835986 0.0959981 0.08631414 -0.07360184 0.03645968 0.04389894 -0.06234282 0.08968394 0.08007282 0.07897102 0.04135018 -0.06167989 0.07905447 0.04511594 -0.05888813 -0.0478273 0.1030898 0.08705604 -0.03794789 0.1083005 0.08770316 -0.04376095 -0.07340216 0.03690361 -0.1194702 -0.02181708 0.1236055 -0.1214436 0 0.1236049 -0.02498823 -0.09737038 0.05039465 -0.02912145 -0.09487253 0.05005937 -0.02488493 -0.09082299 0.04008078 -0.03138554 -0.08557766 0.03885173 -0.03066891 -0.07645106 0.02763319 -0.03840798 -0.0791639 0.03778725 -0.01887142 -0.09459179 0.04067313 -0.02188014 -0.08163839 0.02570199 -0.005578219 -0.1067259 0.05306398 -0.01519042 -0.1123627 0.07489341 -0.03650832 -0.1030226 0.07278019 0.007073879 -0.1097791 0.05278795 -0.002281188 -0.1157939 0.07616209 -0.01781195 -0.0876286 0.02978974 -0.01216769 -0.09151458 0.03077656 -0.01184999 -0.08492588 0.02170509 -3.69617e-4 -0.1037994 0.04345917 -0.006352365 -0.0888229 0.02274328 0.008059322 -0.09937679 0.02985179 0.02075779 -0.1015814 0.02783787 0.005676269 -0.08356672 0.007883906 0.02107411 -0.09235066 0.01118898 0.03974133 -0.09084874 4.57191e-4 0.03133016 -0.08713859 -0.001684486 0.04785448 -0.07904511 -0.02028626 0.06499958 -0.07749128 -0.02962303 0.04899805 -0.06597834 -0.0348401 0.09910112 -0.008728146 -0.08240699 0.0589416 -0.07382237 -0.03163725 0.09972888 -0.01542347 -0.08203905 0.06768536 -0.05297619 -0.05413073 0.07864135 -0.04155886 -0.0655629 0.08274334 -0.03302186 -0.07063162 -0.11883 -0.02173811 0.120631 0.121045 -0.007589817 -0.09164512 0.1435579 -0.01339763 -0.1001239 -0.116973 -0.03032684 0.1207755 -0.1136022 -0.04296028 0.1236075 -0.1130667 -0.04282408 0.1210031 0.1002646 -0.02163237 -0.08138579 -0.1075064 -0.05548936 0.1212587 -0.1040935 -0.06262135 0.1236136 -0.1093656 -0.02086561 0.09225744 0.08435153 -0.03753542 -0.06986498 -0.1036745 -0.06245487 0.1214122 -0.1076832 -0.02911317 0.09252601 0.07157552 -0.05731093 -0.05308371 -0.09262555 -0.07876825 0.1236419 -0.1041023 -0.0411244 0.09296441 -0.08379578 -0.08780276 0.1222157 -0.08487558 -0.08705711 0.1236404 0.08951461 -0.04812163 -0.0676527 -0.07670861 -0.09446507 0.1236573 0.08997923 -0.05060666 -0.06649625 -0.09896695 -0.05331808 0.09347528 0.1212984 -0.01760131 -0.0909639 -0.09462118 -0.01978296 0.06608778 0.1022185 -0.02915668 -0.08068567 -0.09541475 -0.06003761 0.09378999 0.08784848 -0.04475176 -0.06851351 0.08314621 -0.05323016 -0.06153774 -0.09313392 -0.02760541 0.0664125 -0.06699639 -0.1014557 0.1225595 -0.06020921 -0.1059635 0.1237092 0.07910495 -0.06480205 -0.05047106 0.0929262 -0.06416302 -0.05773305 -0.08515053 -0.07520127 0.09460878 -0.08992838 -0.03900623 0.06695771 0.1034591 -0.03358078 -0.08009099 -0.05537861 -0.1084867 0.1228707 -0.05027997 -0.1111976 0.1237472 -0.03989195 -0.1155236 0.1237912 -0.07688325 -0.08461081 0.09522813 0.1440184 -0.02673506 -0.09885871 0.104725 -0.03729808 -0.07951188 -0.08529549 -0.05059748 0.0676108 0.08930015 -0.0605272 -0.05921894 -0.07007879 -0.09098923 0.09568572 0.1226942 -0.02560007 -0.0904051 -0.08207875 -0.05699604 0.06802034 0.1071791 -0.04305744 -0.07860821 -0.06119167 -0.09805679 0.09628373 0.123556 -0.03073692 -0.08982795 0.09635955 -0.05770969 -0.06498557 0.1133111 -0.05592578 -0.07528233 -0.02546447 -0.1198821 0.1238811 -0.01029658 -0.1225575 0.1239885 -0.0529657 -0.1035619 0.0968728 -0.07373958 -0.03662365 0.0440337 0.107728 -0.04526799 -0.07795393 -0.07275509 -0.07147926 0.06910574 -0.04545432 -0.1077117 0.09726804 0.1250012 -0.03784888 -0.08882105 -0.06527298 -0.08043527 0.06988424 0.1112458 -0.05226659 -0.07631981 -0.06934219 -0.04750591 0.04447329 0.1256121 -0.04058164 -0.08835381 0.1453863 -0.04780083 -0.09510034 0.1274304 -0.04743856 -0.08706861 0.1285299 -0.05117899 -0.08625739 -0.06623387 -0.05328828 0.04451227 -0.05902099 -0.08666604 0.07056605 -0.05090761 -0.09352713 0.07138925 -0.02215987 -0.1168925 0.09877872 -0.008082509 -0.120018 0.09966593 -0.05834716 -0.0673545 0.0467382 -0.04333853 -0.09895575 0.0721876 -0.0530548 -0.06575495 0.0393992 -0.0508781 -0.07584744 0.04688847 -0.04543256 -0.08171182 0.04785704 -0.03791856 -0.08824121 0.0486496 -0.0325694 -0.09240889 0.04946321 0.2785042 0.01557391 0.0397982 0.2763976 0.03099995 0.0389471 0.267195 0.03099995 0.05662506 0.2783114 0 0.04223585 0.2843964 0 0.02346032 0.2691006 0.01557391 0.05786257 0.2842883 0.01557391 0.02027153 0.282058 0.03099995 0.01983803 0.2869294 0 0.00388664 0.2547884 0.03099995 0.07222229 0.2396337 0.03099995 0.08516573 0.2409366 0.01557385 0.08702641 0.2862402 0.01557391 0 0.2839681 0.03099995 0 0.2858242 0 -0.01581931 0.2842883 0.01557391 -0.02027159 0.282058 0.03099995 -0.01983803 0.2811183 0 -0.03498703 0.2785042 0.01557391 -0.03979825 0.2763976 0.03099995 -0.0389471 0.2564272 0 0.07488572 0.2413727 0 0.08764922 0.2729719 0 -0.05296432 0.2691006 0.01557391 -0.05786257 0.267195 0.03099995 -0.05662506 0.2616623 0 -0.06913954 0.2564229 0.01557391 -0.07380062 0.2547884 0.03099995 -0.07222229 0.2475741 0 -0.08296233 0.2409369 0.01557391 -0.08702689 0.2396337 0.03099995 -0.08516573 0.2311867 0 -0.09396231 0.2232118 0.01557391 -0.09705525 0.2222877 0.03099995 -0.09497958 0.2130576 0 -0.1017654 0.2038989 0.01557391 -0.1035173 0.2033877 0.03099995 -0.1013035 0.193804 0 -0.1061058 0.18458 0.01557391 -0.1061415 0.1836284 0.03099995 -0.1039048 0.1846127 0 -0.1069005 0.17542 0.01557391 -0.1061415 0.1637358 0.03099995 -0.1026881 0.1753873 0 -0.1069005 0.166196 0 -0.1061059 0.1633815 0.01557391 -0.1049324 0.1584696 0 -0.1048115 0.1510656 0.01557391 -0.1022242 0.1508586 0 -0.1029552 0.2564236 0.01557391 0.07379984 0.2688814 0 0.0595743 0.04584926 0.1166947 0.1138325 0.04361921 0.0965203 0.02539283 0.04792231 0.09705495 0.02830266 0.07662248 0.1041562 0.09524846 0.08222842 0.1004565 0.1076264 0.09090584 0.09687638 0.09423422 0.07853126 0.09883815 0.05965852 0.08029347 0.09796929 0.05872637 0.05981451 0.1107261 0.08928954 0.05595248 0.1128292 0.09808802 0.07451301 0.09023392 0.02613079 0.08015131 0.08428496 0.01425445 0.04389083 0.1170771 0.1245213 0.04981201 0.1150957 0.1217857 0.04688501 0.08862173 0.00821042 0.02980953 0.1140435 0.0704168 0.03450918 0.113812 0.07199043 0.07006883 0.0821076 0.002486228 0.04920619 0.0998913 0.03622204 0.08088928 0.07167172 -0.01616489 0.04179728 0.1174798 0.1031967 0.03979754 0.1184486 0.1129183 0.07603806 0.09380316 0.0381568 0.03216117 0.1134409 0.06931918 0.08279401 0.0984438 0.06566774 0.05136352 0.09023427 0.01325035 0.0512939 0.1148231 0.1144225 0.04800742 0.1035208 0.04566991 0.03742456 0.1099545 0.05973953 0.05376976 0.1042403 0.05167293 0.04968178 0.1084364 0.06273144 0.08185911 0.09709441 0.05750238 0.05950742 0.1088324 0.07588511 0.07903456 0.09314912 0.03915369 0.08286219 0.08825314 0.02766203 0.07931125 0.07931417 9.11164e-4 0.05423259 0.1095671 0.0719558 0.057334 0.107345 0.06612342 0.05864912 0.1100232 0.08119279 0.03483289 0.1123088 0.06657099 0.09292918 0.09348034 0.1088948 0.08968663 0.09438723 0.1140951 0.07378798 0.1041114 0.07819509 0.08452153 0.1000344 0.08375209 0.05407238 0.1123906 0.08741289 0.04796296 0.1158131 0.1045089 0.08307456 0.09117406 0.03704005 0.0441749 0.1161363 0.09510213 0.02642691 0.118875 0.09051817 0.03680688 0.1176097 0.09328752 0.04037922 0.1152209 0.08310258 0.08050245 0.1021938 0.08918368 0.0812776 0.09282863 0.04057085 0.05360192 0.09647464 0.02943438 0.0829631 0.09274852 0.04227983 0.09530407 0.05228751 -0.05268263 0.08116298 0.06067764 -0.03988415 0.06285977 0.07499343 -0.01614081 0.08750861 0.09071177 0.04078727 0.0363897 0.1112196 0.06348383 0.0840016 0.09567517 0.05488753 0.06524473 0.1078063 0.1247801 0.06329536 0.1086893 0.08269804 0.084625 0.09294134 0.04505878 0.08548074 0.09367877 0.04903799 0.08498108 0.09470611 0.05238252 0.0845195 0.09517216 0.1251184 0.1009135 0.08048111 0.1255789 0.09570711 0.09450942 0.08883351 0.06057494 0.1113262 0.1033213 0.0566861 0.1126458 0.1161465 0.07123547 0.1065279 0.1060107 0.06665205 0.1078075 0.1184732 0.08622455 0.06212472 -0.03497964 0.09452033 0.09428524 0.07195752 0.08987909 0.09151345 0.04704767 0.05575907 0.09087926 0.01651406 0.09747648 0.09185534 0.103 0.04195392 0.1131092 0.07458472 0.1016331 0.08137178 0.1224948 0.08699905 0.09486877 0.1195116 0.05041486 0.1145479 0.09675717 0.05339998 0.1140445 0.1055056 0.05584102 0.09752112 0.03341072 0.06021028 0.09948891 0.04187101 0.03781586 0.1088541 0.05646508 0.09422767 0.09131228 0.05353754 0.04783332 0.1138718 0.08546954 0.1018069 0.0900644 0.09834432 0.04734885 0.1122879 0.0762394 0.1047314 0.08091437 0.1180302 0.05748128 0.1024094 0.04874813 0.1064448 0.04402607 -0.06693816 0.1023033 0.08971709 0.06461048 0.1047464 0.08874976 0.09554553 0.1155334 0.06306076 0.1262675 0.1196641 0.06240046 0.122405 0.1083586 0.0735867 0.1239641 0.1053798 0.0894227 0.07934057 0.06721204 0.1079014 0.08825647 0.1083801 0.08005696 0.1138781 0.05768102 0.1032516 0.05161589 0.0591613 0.1039525 0.05521047 0.1083813 0.08709025 0.09223723 0.04665732 0.1107208 0.0688017 0.1116864 0.07311326 0.1199724 0.07530426 0.1017884 0.1249403 0.0769068 0.1017768 0.1195393 0.03730869 0.1017093 0.0362243 0.04019254 0.1026926 0.03974199 0.1124891 0.08562123 0.07500839 0.1133818 0.07853877 0.1093605 0.05801987 0.1012796 0.04563921 0.1242383 0.06153976 0.1190569 0.1155635 0.07225334 0.1163427 0.03677093 0.0956012 0.02141952 0.03702837 0.09683352 0.02425295 0.1141517 0.08432012 0.08749926 0.03906506 0.09262961 0.01519995 0.1196035 0.0373671 -0.07872319 0.1180132 0.07690662 0.1059423 0.06382024 0.1061293 0.06935995 0.1324525 0.03361523 -0.08693867 0.1198812 0.08143544 0.08367258 0.04395604 0.1040955 0.04521465 0.1265494 0.07752877 0.08525425 0.05824118 0.09282177 0.02248275 0.06817424 0.1056852 0.07462543 0.1212036 0.07569336 0.1038964 0.1343357 0.05860507 0.1144104 0.1208238 0.07075726 0.112514 0.1772372 0.04703313 0.09952151 0.1595128 0.05611389 0.09775316 0.1770741 0.0438683 0.1063159 0.1253733 0.06934189 0.1097602 0.006486594 0.1234915 0.1216582 0.1250095 0.07419145 0.1016634 0.06118273 0.104047 0.05763494 0.004251837 0.1229653 0.1131809 0.01062554 0.1234118 0.1242064 0.1288629 0.068057 0.1081 0.009940028 0.1232386 0.1186561 0.1305424 0.07192152 0.09876114 0.1394576 0.03275805 -0.09038531 0.14673 0.03258824 -0.09330105 0.1332224 0.0707612 0.09749448 0.01012641 0.122838 0.1125137 0.1484252 0.05385273 0.1106798 0.1328805 0.0665633 0.1063561 0.1364534 0.06938815 0.09601879 0.0174238 0.1228439 0.1227908 0.1392848 0.06411862 0.1038985 0.1400174 0.06782543 0.09453886 0.01801079 0.1225062 0.1152087 0.02225708 0.1222257 0.1243034 0.1432911 0.06257188 0.1024987 0.06374764 0.1037495 0.05933982 0.02207267 0.1221768 0.119418 0.1430293 0.06654894 0.09317499 0.1468811 0.06112539 0.1014089 0.1511608 0.05937212 0.1001839 0.0162695 0.1220794 0.1075729 0.02056843 0.121532 0.1055819 0.05280166 0.1114084 0.0790354 0.02405822 0.1215205 0.1107725 0.06227415 0.0983653 0.04009568 0.03248757 0.120283 0.1243959 0.06583368 0.1032992 0.06008219 0.03046941 0.1207156 0.117413 0.06383937 0.07911461 -0.0070495 0.01333242 0.1163197 0.07476472 0.06854969 0.1025307 0.06044685 0.03356903 0.1200448 0.1177172 0.0655446 0.09559625 0.03446263 0.0207687 0.1192134 0.08923125 0.02313297 0.1206133 0.09970152 0.06405705 0.0975641 0.03909134 0.06346923 0.0908606 0.02029997 0.01569944 0.1125656 0.06206184 0.06706148 0.09646493 0.03817331 0.03798377 0.1189188 0.1228418 0.02097278 0.1142886 0.06849104 0.02122873 0.1165928 0.07709729 0.0233699 0.1145349 0.06992632 0.03270691 0.1200094 0.1102414 0.01831883 0.1136881 0.06598168 0.07591384 0.09998267 0.06045031 0.07462811 0.1013324 0.06437122 0.02713024 0.1144469 0.07084769 0.03452092 0.1190449 0.1018036 0.02974647 0.1163036 0.07956033 0.029931 0.1224742 0.02189815 0.0321418 0.1206348 0.02174359 0.03387391 0.118337 0.02162247 0.02735888 0.1237576 0.02207803 0.02456212 0.1244168 0.0222736 0.03522694 0.1151574 0.02152782 0.01068639 0.112872 0.0232439 0.02168899 0.1244168 0.02247452 0.01889222 0.1237576 0.02267009 0.0163201 0.1224742 0.02284991 0.01410931 0.1206348 0.02300453 0.0123772 0.118337 0.02312564 0.01121562 0.1157028 0.02320688 0.0116766 0.1120402 0.03744339 0.0139752 0.1160592 0.04597806 0.014521 0.1142042 0.05378359 0.01644128 0.1154636 0.05744701 0.0149281 0.1200527 0.03471386 0.01715159 0.1218831 0.03474086 0.02689868 0.1200587 0.05452555 0.02733981 0.1181417 0.06083387 0.03076457 0.11725 0.06029683 0.03032684 0.1191523 0.05403691 0.02975696 0.1210891 0.04588723 0.03215104 0.1181945 0.05364638 0.0157389 0.1183121 0.04630833 0.01797497 0.1201155 0.04651504 0.01284766 0.1136833 0.04557853 0.03158581 0.1201155 0.04556328 0.03308892 0.1199157 0.03343027 0.03547191 0.1160592 0.04447489 0.03467684 0.1177662 0.03310501 0.01318013 0.1177662 0.03460824 0.03389871 0.1181771 0.04501128 0.0120691 0.1153545 0.03444552 0.02438604 0.1181509 0.06104344 0.02193272 0.1176417 0.06104511 0.03683042 0.1128374 0.047674 0.03668832 0.1118571 0.03758168 0.02394485 0.120068 0.05473464 0.03619503 0.1133398 0.05576807 0.03076249 0.1218831 0.03378909 0.02632439 0.1220105 0.04631274 0.03460985 0.1156142 0.05558204 0.02892684 0.1228713 0.03401595 0.02149349 0.1195505 0.05476397 0.0189743 0.1163078 0.06080687 0.0233705 0.12202 0.04652118 0.0325852 0.1163078 0.0598551 0.0185402 0.1181945 0.05459815 0.02548784 0.1238065 0.03434962 0.02092164 0.1214938 0.04658651 0.02253395 0.1238161 0.03455716 0.03582024 0.1151448 0.03276377 0.02008873 0.1232821 0.03467488 -0.01999998 0.128 0.08999997 0.01999998 0.128 0.08999997 -0.01999998 0.128 0.105 0.01999998 0.128 0.105 -0.06514453 -0.1140333 0.1261825 0.05893582 0.1207283 0.1270257 -0.1151932 0.08216643 0.1290306 0.05484962 0.1128596 0.1246391 -0.1147927 0.1114569 0.1348621 -0.1302585 0.09291243 0.1348621 0.05230551 0.1376376 0.1307973 -0.04805201 -0.1391796 0.1307973 0.0361976 0.1427225 0.1307973 0.04005086 0.1549347 0.1349084 -0.03498119 -0.1561644 0.1348809 -0.05762839 -0.1492614 0.1348621 0.05853307 0.148909 0.1348621 -0.03059017 -0.1440285 0.1307973 0.06887906 0.1138919 0.1266785 -0.05488353 -0.1215913 0.1267615 0.06459397 0.1323162 0.1307973 0.07680183 0.1403619 0.1348621 0.07919901 0.107267 0.1267427 -0.06056684 -0.1342074 0.1307973 -0.07855081 -0.1394475 0.1349002 0.07624143 0.1259651 0.1307973 0.09385019 0.1295845 0.1348621 0.09087818 0.09697377 0.1266232 0.08757096 0.1183693 0.1307973 0.1094072 0.1167479 0.1348621 0.1006828 0.1074381 0.1307973 0.1125146 0.0874595 0.1293334 0.1262934 0.09823429 0.1348621 0.140082 0.07731127 0.1348621 -0.08389204 -0.1033664 0.1266857 0.125935 0.04311841 0.1266821 -0.0730015 -0.12787 0.1307973 -0.09845989 -0.126194 0.1349013 0.1292099 0.07060295 0.1307973 0.1504348 0.05449205 0.1348621 0.1333068 0.02200728 0.127245 0.1392677 0.04779601 0.1307973 0.1570978 0.03033626 0.1348621 0.1375768 0 0.1279439 0.1452695 0.02401554 0.1307973 0.1599076 0.00543642 0.1348621 0.1472412 0 0.1307973 0.1587954 -0.01959669 0.1348621 0.1356883 -0.0117073 0.1275486 0.1461327 -0.01803344 0.1307973 0.1328927 -0.0231958 0.1271884 -0.09531366 -0.08906775 0.125939 0.1291705 -0.03441494 0.1268401 0.1422756 -0.03791606 0.1307973 0.1537883 -0.04414921 0.1348621 0.1245492 -0.04532855 0.1265237 0.1383647 -0.05035042 0.1307973 0.1450092 -0.0676189 0.1348621 0.1169075 -0.05961817 0.12616 -0.09282207 -0.114298 0.1307973 -0.1169107 -0.1092331 0.1348621 0.1311956 -0.06684076 0.1307973 0.133255 -0.0885902 0.1348692 0.1078467 -0.07294666 0.1258741 -0.09417647 0.09127384 0.1261332 -0.1019604 -0.06992936 0.1241624 0.1219682 -0.08248466 0.1307973 0.1184728 -0.107558 0.1348686 0.0927816 -0.08817285 0.1252672 -0.1088616 -0.07467484 0.1263753 -0.1056388 0.102569 0.1307973 -0.07485842 0.0986756 0.1242154 -0.107588 -0.1005226 0.1307973 0.1067031 -0.1014614 0.1307973 0.1010327 -0.1240844 0.1348686 0.07574218 -0.1012269 0.1248899 0.06628787 -0.1068997 0.1247246 0.08003526 -0.1069965 0.1268216 -0.08139026 0.1072276 0.1271017 -0.1120671 -0.0542559 0.1243855 0.06743657 -0.1145641 0.1266327 0.05513787 -0.1123782 0.1245619 0.08821159 -0.1178927 0.1307973 0.08133316 -0.1378002 0.1348685 -0.1214261 -0.08328062 0.1307973 -0.1319479 -0.09049707 0.1348621 -0.1212061 -0.05868542 0.127115 -0.08900016 0.1172985 0.1307973 -0.09671229 0.1274627 0.1348621 0.04527038 -0.1162547 0.124447 -0.06271517 0.1155678 0.1262257 0.07485347 -0.1267948 0.1307973 0.06086385 -0.1479947 0.1349008 0.05014115 -0.1246796 0.1270366 -0.1325266 -0.06416118 0.1307973 -0.1440105 -0.06972074 0.1348621 -0.1260959 -0.03897392 0.126367 0.03437286 -0.1194989 0.1243435 -0.1214174 -0.01840525 0.123945 -0.1406395 -0.04359477 0.1307973 -0.1528262 -0.04737251 0.1348621 0.03658699 -0.1281634 0.1267297 -0.05164998 0.1195664 0.1258856 0.02306026 -0.1217643 0.1242386 0.01164019 -0.1230323 0.1241464 0.0550251 -0.1365731 0.1307973 -0.1319588 -0.01985305 0.1267718 -0.1397271 0 0.1285232 0.02466619 -0.1296746 0.1263665 -0.1455813 -0.02204692 0.1307973 -0.1581964 -0.02395629 0.1348621 -0.16 0 0.1348621 -0.07035845 0.1293432 0.1307973 -0.07642912 0.1405652 0.1348621 0.04042768 -0.1415824 0.1307973 0.03695923 -0.1556922 0.1348753 0.01073837 -0.131541 0.1263647 7.41337e-4 -0.1232677 0.1240687 0.02739977 -0.1446692 0.1307973 0.01317334 -0.1594743 0.1348698 -0.04152327 0.1270189 0.1268242 -0.009145557 -0.1332662 0.126811 -0.0583623 0.1351806 0.1307973 -0.05440509 0.1504662 0.1348621 0.01212161 -0.1467414 0.1307973 -0.02536678 0.1287295 0.1261504 -0.04569572 0.139971 0.1307973 -0.03114193 0.15694 0.1348621 -0.005890488 0.1297132 0.1257796 -0.02777051 -0.1306098 0.1267966 -0.02865856 0.1444252 0.1307973 -0.009986162 -0.1469022 0.1307973 -0.01089012 -0.1596434 0.1348692 0.007104992 0.1343225 0.1270709 -0.006597757 0.1470932 0.1307973 -0.006877601 0.1599394 0.1348884 -0.04384207 -0.1269887 0.1270253 0.02012252 0.1326022 0.1269638 0.007787227 0.1470351 0.1307973 0.01024341 0.1620108 0.1355969 0.03306311 0.1304388 0.1270861 0.02209788 0.1455734 0.1307973 0.02439868 0.1637095 0.1365889 0.04754322 0.1248693 0.1268203 -0.1335149 0.09523528 0.1223715 -0.1320328 0.09417808 0.1415503 -0.1335149 0.09523528 0.1483502 -0.1394229 0.08641433 0.1223708 -0.1728043 0.0698195 0.1229551 -0.1624694 0.09132176 0.1229574 -0.1441326 0.07824176 0.1223566 -0.1803049 0.04718309 0.1229535 -0.1848508 0.0237931 0.1229581 -0.1863759 0 0.1229575 0.2755916 -0.02681332 0.04393523 0.2794094 -0.02600377 0.03477811 0.2127928 -0.01703566 -0.1011167 0.1925418 -0.01851552 -0.1054486 0.1930016 -0.01556116 -0.1056148 0.2303076 -0.02719724 -0.09233611 0.2341129 -0.03820288 -0.08801233 0.2177157 -0.03926688 -0.09596163 0.2125062 -0.02674657 -0.1000641 0.2635761 -0.04531162 0.05813467 0.2765865 -0.01684522 0.04442757 0.2803927 -0.01613706 0.03513401 0.2648128 -0.03840559 0.05894672 0.273846 -0.03840446 0.04313832 0.2308071 -0.01703703 -0.09337329 0.2464586 -0.02650278 -0.08161473 0.2499411 -0.03762686 -0.07619601 0.2527143 -0.04678273 0.07077336 0.2515302 -0.05314922 0.06960767 0.2625222 -0.05058515 0.05735999 0.2367765 -0.05604594 0.08108538 0.2389663 -0.04073947 0.08421254 0.2663726 -0.02691322 0.06003981 0.2471678 -0.0162115 -0.08246368 0.2601711 -0.02790242 -0.06787735 0.26205 -0.03764516 -0.0629636 0.2610157 -0.01888161 -0.06859219 0.2672932 -0.01697999 0.06067156 0.2540153 -0.0384255 0.07203495 0.271482 -0.02619189 -0.0521273 0.271698 -0.03818559 -0.04760915 0.240458 -0.02517992 0.08634293 0.2553725 -0.02704328 0.07335036 0.2776477 -0.03818082 -0.03378385 0.2785563 -0.03926897 -0.03028982 0.2724131 -0.01621145 -0.05264598 0.1593547 -0.04169046 -0.100547 0.1635683 -0.04511016 -0.100509 0.2795752 -0.02557557 -0.03447252 0.2561815 -0.01720291 0.07411736 0.1674015 -0.03948557 -0.1023148 0.2820674 -0.03907269 -0.01503813 0.28209 -0.04085505 -0.01190966 0.1587893 -0.02555221 -0.1032211 0.2805131 -0.01623433 -0.03475302 0.2840554 -0.0267601 -0.01554507 0.1722374 -0.04042047 -0.1026009 0.1807616 -0.04290765 -0.1023403 0.2829449 -0.03991347 0.003637254 0.2821342 -0.04286634 0.006674587 0.158542 -0.01623439 -0.1041647 0.1775797 -0.03979027 -0.1029884 0.2851253 -0.01703828 -0.01576697 0.166983 -0.02780473 -0.1042615 0.2852532 -0.02598083 0.003843545 0.1666724 -0.0224151 -0.1049184 0.2791705 -0.04500585 0.02336525 0.1807725 -0.03831768 -0.1032988 0.2808203 -0.03818893 0.02262622 0.1696653 -0.02288061 -0.1051806 0.1718686 -0.0251404 -0.1050993 0.1741998 -0.02664226 -0.1050867 0.2862869 -0.01618647 0.00383377 0.1807207 -0.02797901 -0.1050306 0.1838269 -0.02741098 -0.1050403 0.2758343 -0.04649174 0.03355163 0.1680805 -0.02016901 -0.1053136 0.1671706 -0.0172168 -0.1055133 0.2774977 -0.03829735 0.0341506 0.186751 -0.04033547 -0.1026924 0.2826659 -0.02664464 0.0230714 0.1775712 -0.02776384 -0.1050373 0.2719538 -0.04787492 0.042288 0.192372 -0.04081618 -0.1020821 0.1989884 -0.0409193 -0.1009992 0.186678 -0.02614617 -0.1050801 0.1892086 -0.02417594 -0.1051309 0.2837299 -0.01687085 0.02329045 0.1932911 -0.027417 -0.1042963 0.1911246 -0.02171099 -0.1052472 0.2119241 -0.03817462 -0.09827268 0.0726459 -0.09583735 0.01768815 0.05613368 -0.09943485 0.02338558 0.07749825 -0.1055933 0.06448721 0.06409031 -0.1106505 0.08101367 0.0533275 -0.1127486 0.07653117 0.07548242 -0.1073831 0.0858969 0.06670409 -0.1071346 0.05822348 0.07242232 -0.08357161 -0.01556044 0.05712431 -0.08776694 -0.006916642 0.07471978 -0.07867377 -0.02679306 0.07303422 -0.1002528 0.03282392 0.06242239 -0.1007656 0.02951866 0.08866488 -0.09813177 0.1088381 0.07164466 -0.1059522 0.1138103 0.07659357 -0.10514 0.1052766 0.08334177 -0.09874856 0.1162557 0.08638739 -0.09427493 0.01911169 0.07023751 -0.09241425 0.006844997 0.05777925 -0.09113752 0.00132817 0.08239585 -0.1003971 0.04043316 0.0568633 -0.1077394 0.05263477 0.08807301 -0.1024185 0.09147989 0.06441986 -0.1106028 0.101846 0.09656423 -0.08826726 0.1191967 0.08896231 -0.1029083 0.07130622 0.09043717 -0.09700447 0.03259497 0.09663248 -0.09818565 0.04572534 0.1045445 -0.09747326 0.05754369 0.1023936 -0.08784127 0.1131273 0.1006423 -0.09588038 0.09727919 0.1048499 -0.08008641 0.121163 0.1123062 -0.07297921 0.1216077 0.1016889 -0.09857797 0.07910037 0.1147618 -0.09461838 0.06864374 0.1110589 -0.07975697 0.1160016 0.1175058 -0.07272666 0.1182487 0.1144676 -0.09266018 0.08719938 0.1150746 -0.08608484 0.104277 0.1242859 -0.07828223 0.1089807 0.1312081 -0.0714398 0.1126697 0.1446009 -0.08163976 0.0868287 0.1292583 -0.08355444 0.0969845 0.1252715 -0.05639421 -0.07421422 0.1387848 -0.0761739 0.1035748 0.1460015 -0.06963562 0.1087538 0.1370772 -0.05353647 -0.08115416 0.1431112 -0.08078128 0.09097927 0.1612951 -0.074763 0.09097915 0.1533038 -0.07383197 0.09906965 0.1707438 -0.06625187 0.103575 0.1496647 -0.05137544 -0.08685362 0.1575626 -0.07322806 0.09755414 0.1777675 -0.06959837 0.09176701 0.1016335 -0.09234672 0.1055863 0.200341 -0.0619257 0.09659707 0.2191293 -0.05902254 0.09014904 0.2324992 -0.05876517 0.07283765 -0.003331959 -0.1225358 0.1159397 0.001819074 -0.1227299 0.1158047 0.001605689 -0.1211085 0.1010726 0.01181566 -0.1226361 0.1164343 0.001938283 -0.1185111 0.08614909 0.01804929 -0.1223487 0.120416 0.00712943 -0.119005 0.08734053 0.0139212 -0.1213873 0.1032053 0.02641862 -0.1211172 0.1185584 0.02099627 -0.1210215 0.104398 0.0175811 -0.1194059 0.08981186 0.01451605 -0.1129642 0.06134563 0.02928024 -0.1200876 0.1058292 0.02478265 -0.1191968 0.09155744 0.03322261 -0.1184422 0.09364867 0.03871589 -0.118342 0.1075067 0.02754956 -0.1141175 0.06625449 0.04712116 -0.1159755 0.1165763 0.02815395 -0.1053063 0.03692609 0.03488212 -0.1142396 0.06911551 0.04284858 -0.1168951 0.09609615 0.04348933 -0.1138674 0.07253587 0.04096227 -0.1071467 0.04383182 0.04013848 -0.09655189 0.01383572 0.05334842 -0.1143398 0.09884655 0.05979806 -0.1116312 0.1114538 0.0458132 -0.09739446 0.0161637 0.04762113 -0.09242391 0.003854155 0.04827111 -0.1076581 0.04784429 -0.1853797 0 0.161 -0.1627054 0 0.1434358 -0.1648792 0 0.1521593 -0.166513 0 0.161 0.1650277 0.03258824 -0.09791737 0.1838688 0.03258824 -0.09897989 0.2025694 0.03258824 -0.09644997 0.2204509 0.03258824 -0.09041959 0.2368644 0.03258824 -0.08110749 0.251214 0.03258824 -0.06885164 0.2629789 0.03258824 -0.05409693 0.2717322 0.03258824 -0.03737884 0.2771562 0.03258824 -0.01930415 0.279054 0.03258824 -5.28825e-4 0.2773568 0.03258824 0.01826566 0.2721261 0.03258824 0.03639727 0.2635518 0.03258824 0.05320787 0.2519451 0.03258824 0.06808739 0.2377271 0.03258824 0.08049571 0.2312753 0.03099006 0.09048295 0.2214141 0.03258824 0.0899825 0.2225521 0.03094828 0.09503549 0.203598 0.03258824 0.0962035 0.2041335 0.03069424 0.1020682 0.1849285 0.03260892 0.09893429 0.1849234 0.02991789 0.1070619 0.1387034 0.04959243 0.1155204 0.1421806 0.04099434 0.1165429 0.1553661 0.03762358 0.1126473 0.1522861 0.04553174 0.1117221 0.18 0.03511011 0.1073217 0.1508188 0 0.1208099 0.1698002 0 0.1142676 0.1584759 0.02766382 0.1137289 0.1456907 0.03015297 0.1177594 0.18 0.03885805 0.1066616 0.2006624 0 0.1057705 0.1842004 0.02247816 0.1082339 0.195904 0.0273469 0.1048583 0.197823 0.02007615 0.1052561 0.2125838 0.02406382 0.1003482 0.2268666 0.02451461 0.09422689 0.2139587 0.01764386 0.1006354 0.2159572 0 0.1007465 0.2279034 0.01617127 0.09485882 0.2290918 0 0.09502291 0.1245778 0.05251795 0.1234066 0.1281183 0.04407608 0.1241809 0.1323042 0.03221189 0.1251108 0.193804 0 -0.108 0.166196 0 -0.108 0.06647139 0.1090002 0.05994337 0.06350928 0.109 0.05888283 0.06139492 0.109 0.05742335 0.05969125 0.109 0.05550032 0.0584973 0.109 0.05322539 0.05788242 0.109 0.05073088 0.05788242 0.109 0.04816174 0.0584973 0.109 0.04566723 0.05969125 0.109 0.0433923 0.06139492 0.109 0.04146927 0.06350928 0.109 0.04000979 0.06591153 0.109 0.03909873 0.06846195 0.109 0.03878909 0.07396197 0.109 0.06010353 0.07651239 0.109 0.05979382 0.07567811 0.109 0.03889417 0.07891464 0.109 0.04000979 0.08102899 0.109 0.04146927 0.08273267 0.109 0.0433923 0.08392667 0.109 0.04566723 0.08454149 0.109 0.04816174 0.08454149 0.109 0.05073088 0.08392667 0.109 0.05322539 0.08273267 0.109 0.05550032 0.08102899 0.109 0.05742335 0.07891464 0.109 0.05888283 0.1249986 0.03099995 -0.08231544 0.1099964 0.03099995 -0.07000356 0.0976845 0.03099995 -0.05500143 0.18 0.03099995 0.09899997 0.18 0.03775757 0.09923624 0.0885359 0.03099995 -0.0378856 0.1993139 0.03099995 0.09709769 0.2178857 0.03099995 0.09146404 0.08290225 0.03099995 -0.01931393 0.2350014 0.03099995 0.08231544 0.08099997 0.03099995 0 0.2500036 0.03099995 0.07000356 0.2623155 0.03099995 0.05500143 0.08290225 0.03099995 0.01931393 0.2714641 0.03099995 0.0378856 0.2770977 0.03099995 0.01931393 0.0885359 0.03099995 0.0378856 0.279 0.03099995 0 0.0976845 0.03099995 0.05500143 0.2770977 0.03099995 -0.01931393 0.2714641 0.03099995 -0.0378856 0.1099964 0.03099995 0.07000356 0.2623155 0.03099995 -0.05500143 0.2500036 0.03099995 -0.07000356 0.1249986 0.03099995 0.08231544 0.1421143 0.03099995 0.09146404 0.2350014 0.03099995 -0.08231544 0.1606861 0.03099995 0.09709769 0.2178857 0.03099995 -0.09146404 0.1993139 0.03099995 -0.09709769 0.18 0.04263448 0.09940624 0.18 0.03099995 -0.09899997 0.1606861 0.03099995 -0.09709769 0.1421143 0.03099995 -0.09146404 -0.07713371 0.1418611 0.1393074 -0.09760385 0.1286377 0.1393074 -0.07833981 0.1440794 0.1483502 -0.09913009 0.1306492 0.1483502 -0.07960098 0.1463989 0.1618465 -0.09927302 0.1355318 0.1755 -0.07848221 0.1485414 0.1755 -0.100726 0.1327525 0.1618465 -0.05490666 0.1518534 0.1393074 -0.146297 0.07978606 0.1618296 -0.1390833 0.08696442 0.148291 -0.1441324 0.07824212 0.1483502 -0.05576521 0.1542279 0.1483502 -0.05666297 0.1567108 0.1618465 -0.05601882 0.1583853 0.1755 -0.03142905 0.1583869 0.1393074 -0.009557843 0.1599088 0.135421 -0.03192049 0.1608636 0.1483502 -0.009097754 0.1651675 0.1547242 -0.03243434 0.1634533 0.1618465 -0.008880019 0.1677314 0.1745823 -0.03236156 0.1648537 0.1755 -0.008382141 0.1598705 0.1350299 -0.007988572 0.1679534 0.1755015 -0.008026182 0.1679431 0.1750022 -0.1431254 0.08534681 0.1618465 -0.1474128 0.08058196 0.1755 -0.1341094 0.101186 0.1755 -0.1356644 0.09676843 0.1618465 -0.115851 0.1124844 0.1393074 -0.1176625 0.1142433 0.1483502 -0.1195567 0.1160825 0.1618465 -0.1179481 0.1196338 0.1755 -0.00526607 0.1636321 0.1360648 -0.004800498 0.1705266 0.1380485 0.01451408 0.169732 0.1379052 0.03808963 0.1577695 0.1356073 0.03761363 0.170371 0.1389479 0.03803837 0.1639442 0.1373611 0.09802824 0.1353534 0.1654331 0.08448541 0.1452109 0.1755 0.104878 0.1312425 0.1755 0.08022099 0.1466107 0.1654331 0.07937711 0.1450684 0.1544919 0.09699708 0.1339296 0.1544919 0.1087112 0.1245077 0.1538729 0.1049489 0.1245 0.1438905 0.09551185 0.1318789 0.1438905 0.1077141 0.1277801 0.1654331 0.1114892 0.1245 0.1654331 0.04207944 0.1546218 0.1355935 0.1230003 0.1144331 0.1755 0.05956947 0.1515455 0.1438905 0.04173409 0.1585898 0.1482836 0.06049579 0.1539019 0.1544919 0.04149842 0.1614524 0.1619791 0.04311913 0.1623572 0.1751251 0.04059058 0.1629944 0.1749253 0.03912067 0.163385 0.175477 0.06212234 0.1560999 0.1754936 0.07816165 0.1428471 0.1438905 0.06113892 0.1555382 0.1654331 0.1504665 0.1151502 0.141429 0.1643785 0.09748017 0.141633 0.1589283 0.09156888 0.1405878 0.1420792 0.1048149 0.13931 0.1471939 0.1102803 0.1406795 0.1558834 0.08356493 0.1393604 0.165277 0.06587058 0.1396189 0.1222176 0.1162196 0.1374526 0.1487101 0.07885843 0.1373208 0.1571758 0.0599426 0.1373324 0.1658295 0.0458678 0.1383514 0.1714507 0.04264014 0.1393513 0.166323 0.02593564 0.1373352 0.1727142 0.02164697 0.1387863 0.1735745 5.90145e-4 0.1386716 0.1682551 0.002639055 0.1373271 0.1727449 -0.02092301 0.1387764 0.1669977 -0.02022695 0.1373324 0.1714776 -0.04225426 0.1393375 0.1633326 -0.0402472 0.1373324 0.1610035 -0.04873842 0.1373276 0.151726 -0.05741059 0.1355957 0.1480911 -0.06212955 0.135062 0.1339336 0.1018435 0.1372994 0.1349473 0.1157264 0.1395892 0.1639026 0.1147106 0.1423314 -0.1344385 -0.1008455 0.1754953 -0.1181399 -0.1177911 0.1630869 -0.1188816 -0.1187885 0.1754953 -0.1451079 -0.07945024 0.1547321 -0.1309854 -0.09802323 0.1467654 -0.1324604 -0.09911108 0.1547341 -0.1434946 -0.07858139 0.1467654 -0.1462978 -0.08014321 0.1629729 -0.1335635 -0.09996241 0.1630855 0.1418937 -0.08994543 0.1755 0.1499443 -0.06992012 0.1548966 0.1522597 -0.07099986 0.1755 -0.1531385 -0.05757051 0.1467654 -0.147082 -0.08054596 0.1709754 -0.1473517 -0.08069366 0.1755 -0.154846 -0.05815088 0.1545704 -0.1561451 -0.05873388 0.1630685 -0.1635724 -0.0362631 0.1691024 -0.1627065 -0.03607112 0.1619443 -0.157352 -0.05901372 0.1754959 -0.1597244 -0.03541004 0.1467654 -0.161538 -0.03569078 0.15473 0.05290395 -0.1511917 0.135381 0.04016143 -0.1553346 0.1359966 -0.1594439 -0.01746672 0.1360151 -0.1655973 -0.01814079 0.161475 -0.1626295 -0.0178157 0.1467654 -0.1644356 -0.0179612 0.154657 -0.06086975 -0.1480228 0.1350043 -0.1640177 -0.03636181 0.1755 -0.05290484 -0.1511912 0.1353809 0.1362498 -0.09056335 0.1467654 0.137825 -0.09159815 0.1549994 0.1389551 -0.09229874 0.1630178 0.1291829 -0.1074047 0.1755 0.1396561 -0.09282743 0.1709754 0.1211549 -0.109942 0.1467654 0.122504 -0.1111825 0.1547342 0.123515 -0.1120818 0.1628254 0.1143375 -0.1230891 0.1755 0.1241838 -0.1126906 0.1709754 0.1033276 -0.126843 0.1467654 0.1044759 -0.1282716 0.1547351 0.1053573 -0.1293166 0.1629173 0.1059108 -0.1300141 0.1709754 0.09760266 -0.1367396 0.1755 0.08317112 -0.140884 0.1467654 0.08411157 -0.142392 0.1544785 0.08478832 -0.1436409 0.1628749 0.08525037 -0.1444061 0.1709754 0.07925504 -0.1481305 0.1755 0.06282407 -0.1528565 0.1537896 0.06007695 -0.1536638 0.1526325 0.04060107 -0.1584887 0.1467643 0.06344395 -0.1542948 0.1631127 0.05977571 -0.1558181 0.1635064 0.03772926 -0.1591925 0.1467654 0.06377649 -0.1550914 0.1709754 0.05959773 -0.1570736 0.1755 0.03819108 -0.1610196 0.1549916 0.04093235 -0.1608456 0.1576818 0.03851515 -0.1623225 0.1630935 0.04121625 -0.1628656 0.1755 0.0134685 -0.1630471 0.1467654 0.0386725 -0.1631723 0.1709754 0.02076739 -0.1667115 0.1755 0.01360738 -0.1648743 0.1547331 0.01375979 -0.1662414 0.1629666 -0.01109582 -0.1632257 0.1467654 0.01380521 -0.1671233 0.1709754 0 -0.168 0.1755 -0.01123213 -0.1650526 0.1547306 -0.04060107 -0.1584887 0.1467643 -0.04015707 -0.1553135 0.1359968 -0.01129394 -0.1664246 0.1629516 -0.03541004 -0.1597244 0.1467654 -0.01137322 -0.1673064 0.1709754 -0.02076739 -0.1667115 0.1755 -0.03581231 -0.1614636 0.1544979 -0.04093235 -0.1608456 0.1576818 -0.03614681 -0.1628497 0.1629642 -0.04121625 -0.1628656 0.1755 -0.03629529 -0.1637175 0.1709754 -0.05977249 -0.1558564 0.1636281 -0.06007695 -0.1536638 0.1526325 -0.07901912 -0.1432541 0.1467654 -0.07990509 -0.1449303 0.1550478 -0.06106084 -0.1561805 0.1709754 -0.05959773 -0.1570736 0.1755 -0.0811699 -0.1471409 0.1754961 -0.08056867 -0.1461087 0.1632433 -0.09842258 -0.1306857 0.1467654 -0.09955334 -0.1320913 0.1545727 -0.1135913 -0.1132451 0.1360151 -0.1003571 -0.1332676 0.1630872 -0.1158608 -0.1155077 0.1467654 -0.1009507 -0.1343594 0.1754931 -0.1172322 -0.1167917 0.1549876 0.1513938 -0.01138412 0.1192715 0.1658235 -0.01100718 0.1144884 0.1531172 -0.05633229 0.110367 0.1893623 -0.04108583 0.1045649 0.2194682 -0.009394407 0.09906327 0.1398373 -0.03351712 0.1203451 0.1466633 -0.03285515 0.1175533 0.2117295 -0.009643614 0.1018988 0.1359029 -0.03371763 0.1223604 0.1312381 -0.0338611 0.1253639 0.1319013 -0.04507344 0.121297 0.1270253 -0.04525291 0.124462 0.1999444 -0.01020044 0.1055454 0.1978441 -0.02937537 0.1042113 0.2270231 -0.009143054 0.09577059 0.2096758 -0.02806717 0.1007851 0.1359606 -0.04481518 0.1192461 0.204796 -0.03801941 0.100829 0.1196544 -0.05946993 0.1236519 0.1923353 -0.05123484 0.1017985 0.2343147 -0.008889079 0.09192925 0.2177314 -0.02735686 0.09798121 0.1431593 -0.04436391 0.1163107 0.225603 -0.02664005 0.09469985 0.1253902 -0.05929845 0.1198193 0.2162511 -0.03673458 0.09702235 0.2050683 -0.04989916 0.09823739 0.1612752 -0.03170204 0.1130927 0.2332088 -0.02591538 0.09084194 0.2243708 -0.03579229 0.09372347 0.1296496 -0.05898094 0.1177058 0.2137701 -0.04870808 0.09538948 0.232224 -0.03483939 0.08983421 0.1409465 -0.01163488 0.1241775 0.1367593 -0.05835521 0.1148936 0.2222894 -0.04750573 0.09204185 0.144717 -0.01156288 0.1221978 0.2305419 -0.04628956 0.08808648 0.157905 -0.04280155 0.1120482 0.1766288 -0.03083854 0.1093285 -0.1834908 0.02358198 0.1755 -0.185 0 0.1755 -0.178988 0.04677921 0.1755 -0.1715649 0.06921327 0.1755 -0.161341 0.09051686 0.1755 0.1671253 -0.01691663 -0.1075572 0.1677592 -0.01937776 -0.1074926 0.1692201 -0.02226591 -0.1074169 0.1713491 -0.02470374 -0.1073531 0.1740144 -0.02653998 -0.107305 0.1770506 -0.02766096 -0.1072757 0.1802697 -0.02799719 -0.1072669 0.183472 -0.02752774 -0.1072792 0.1864592 -0.02628177 -0.1073118 0.1890459 -0.02433651 -0.1073627 0.191072 -0.02181249 -0.1074288 0.1924118 -0.01886624 -0.107506 0.1929821 -0.01568037 -0.1075894 0.1643774 -0.04922163 -0.0912559 0.1796507 -0.04726779 -0.09308969 0.1984263 -0.04523944 -0.09176242 0.2164922 -0.0436998 -0.08658421 0.2250944 -0.04313164 -0.08257305 0.2332588 -0.04270946 -0.07767558 0.2464241 -0.04233938 -0.06689655 0.2573863 -0.04247736 -0.05378764 0.2664098 -0.04321837 -0.03718364 0.2714508 -0.04439049 -0.02085697 0.2733254 -0.04599267 -0.003914296 0.2719865 -0.04796558 0.01308798 0.2674578 -0.05023705 0.0295329 0.2636319 -0.05159306 0.03818875 0.2589332 -0.05299371 0.04636299 0.253391 -0.05443048 0.05401021 0.2470931 -0.05588096 0.06101483 0.240132 -0.05732548 0.06729018 0.1503587 0.001999974 -0.08512371 0.1319314 0.001999974 -0.07605075 0.116924 0.001999974 -0.06524044 0.1143068 -0.06017017 -0.06582641 0.1072285 0.001999974 -0.05550366 0.09927964 0.001999974 -0.04456502 0.1048018 -0.06463336 -0.0562368 0.09343129 0.001999974 -0.03300023 0.09687781 -0.0696876 -0.04543209 0.08958709 0.001999974 -0.02099901 0.09081375 -0.07496917 -0.03369694 0.08764958 0.001999974 -0.008750498 0.08666133 -0.08039647 -0.02111685 0.08752071 0.001999974 0.003556609 0.08452492 -0.08561754 -0.008004546 0.08999216 0.001999974 0.01973307 0.0844264 -0.0903753 0.005546927 0.0964812 0.001999974 0.03787815 0.08689904 -0.08920466 0.0204938 0.09351009 -0.09182482 0.03928065 0.1028271 -0.09168279 0.05494046 0.1054894 0.001999974 0.0530284 0.1170738 0.001999974 0.06618291 0.1279934 -0.08921718 0.07875621 0.1306656 0.001999974 0.07667958 0.1456807 0.001999974 0.08411639 0.1616549 0.001999974 0.08832347 0.1782916 0.001999974 0.08924382 0.1954405 0.001999974 0.08681529 0.1949394 -0.06561017 0.08935487 0.2313532 0.001999974 0.07105177 0.2134218 -0.06214708 0.0831691 0.2131174 0.001999974 0.08086228 -0.1658438 -0.02100783 0.1615498 -0.1635456 -0.03625714 0.1619493 -0.1788401 -0.01039391 0.1612722 -0.1823164 -0.01047545 0.1612743 -0.1953557 -0.012308 0.1613222 -0.1957599 0 0.161 -0.1674309 -0.01750552 0.1614584 -0.1695763 -0.01476895 0.1613867 -0.1754384 -0.01111495 0.1612911 -0.1722941 -0.01259994 0.1613299 0.1104199 0.03099995 -0.06614083 0.1251582 0.03099995 -0.07879328 0.1174682 0.03099995 0.07284075 0.2559145 0.03099995 0.05876213 0.1040855 0.03099995 0.05876213 0.2661892 0.03099995 0.04227781 0.133411 0.03099995 0.08393728 0.1421418 0.03099995 -0.08821994 0.09381073 0.03099995 0.04227781 0.1512611 0.03099995 0.09159737 0.2729354 0.03099995 0.02406263 0.08706456 0.03099995 0.02406263 0.1606753 0.03099995 -0.09403485 0.1702878 0.03099995 0.09550744 0.2758768 0.03099995 0.004862308 0.08412319 0.03099995 0.004862308 0.18 0.03099995 -0.09599995 0.1897122 0.03099995 0.09550744 0.08510702 0.03099995 -0.01453703 0.2748929 0.03099995 -0.01453703 0.1993247 0.03099995 -0.09403485 0.2087389 0.03099995 0.09159737 0.2700242 0.03099995 -0.03334128 0.08997577 0.03099995 -0.03334128 0.2178581 0.03099995 -0.08821994 0.226589 0.03099995 0.08393728 0.2614698 0.03099995 -0.05078053 0.09853011 0.03099995 -0.05078053 0.2348418 0.03099995 -0.07879328 0.2425318 0.03099995 0.07284075 0.2495801 0.03099995 -0.06614083 -0.007898807 0.1691671 0.1737288 -0.007468402 0.1703226 0.1737783 -0.007673025 0.1690247 0.1745365 -0.008467435 0.1683813 0.1739355 -0.007070124 0.1700868 0.174808 -0.008841693 0.1681001 0.1735947 -0.007273316 0.1686856 0.1750857 -0.006276428 0.1701491 0.1753113 -0.006404101 0.1691301 0.1754164 -0.005414664 0.1697979 0.1755019 -0.006867647 0.1680021 0.1754609 -0.009044408 0.1656186 0.1550816 -0.009515166 0.1604633 0.1361377 -0.008705437 0.160921 0.1361216 -0.008804738 0.1615366 0.1377112 -0.1949999 0 0.1755 -0.1944846 -0.01416826 0.1755 -0.1869457 -0.01937878 0.1755 -0.1853265 -0.01794421 0.1755 -0.1881747 -0.02115917 0.1755 -0.1834109 -0.01693886 0.1755 -0.1889418 -0.02318191 0.1755 -0.1813105 -0.01642113 0.1755 -0.1929411 -0.02826166 0.1755 -0.1892026 -0.02532947 0.1755 -0.1791471 -0.01642113 0.1755 -0.1889418 -0.02747702 0.1755 -0.1770465 -0.01693886 0.1755 -0.1881747 -0.02949982 0.1755 -0.1751311 -0.01794421 0.1755 -0.1869457 -0.03128021 0.1755 -0.1735118 -0.01937878 0.1755 -0.1722829 -0.02115917 0.1755 -0.1903777 -0.04220569 0.1755 -0.1834109 -0.03372013 0.1755 -0.1853265 -0.03271478 0.1755 -0.1813105 -0.03423786 0.1755 -0.1791471 -0.03423786 0.1755 0.03780782 0.1701563 0.1754927 -0.1715157 -0.02318191 0.1755 -0.171255 -0.02532947 0.1755 -0.1715157 -0.02747702 0.1755 -0.1722829 -0.02949982 0.1755 -0.1735118 -0.03128021 0.1755 -0.1751311 -0.03271478 0.1755 -0.1770465 -0.03372013 0.1755 -0.03742551 0.03315609 0.1755 -0.02840322 0.04114913 0.1755 -0.04427278 0.02323615 0.1755 -0.01773023 0.04675078 0.1755 -0.04854708 0.01196575 0.1755 -0.006026804 0.04963541 0.1755 -0.04999995 0 0.1755 0.006026804 0.04963541 0.1755 -0.04854708 -0.01196575 0.1755 0.01773023 0.04675078 0.1755 -0.04427278 -0.02323615 0.1755 0.02840322 0.04114913 0.1755 -0.03742551 -0.03315609 0.1755 0.03742551 0.03315609 0.1755 -0.02840322 -0.04114913 0.1755 0.04427278 0.02323615 0.1755 -0.01773023 -0.04675078 0.1755 0.1627517 0.1144331 0.1755 0.1644384 0.05005997 0.1755 0.04854708 0.01196575 0.1755 0.04999995 0 0.1755 -0.0575 -0.172 0.1755 -0.006026804 -0.04963541 0.1755 0.168 0.04572767 0.1755 -0.04249995 -0.172 0.1755 0.006026804 -0.04963541 0.1755 0.01773023 -0.04675078 0.1755 0.04854708 -0.01196575 0.1755 0.168 -0.04572767 0.1755 0.1592265 -0.05779355 0.1755 0.04427278 -0.02323615 0.1755 0.02840322 -0.04114913 0.1755 0.04249995 -0.172 0.1755 0.0575 -0.172 0.1755 0.03742551 -0.03315609 0.1755 0.04074418 0.1577183 0.1382375 0.04071223 0.1584089 0.1388646 0.04017049 0.159179 0.1373704 0.0414161 0.1557689 0.1366128 0.0409727 0.156704 0.137162 0.03904592 0.1593225 0.1363646 0.0410282 0.1557148 0.1359979 0.04041993 0.1568275 0.136345 0.0401085 0.1560774 0.1355844 0.03826761 0.1702011 0.139076 0.03933525 0.1638006 0.137938 0.03931409 0.1697594 0.1396633 0.0400573 0.1694917 0.1409114 0.01631224 0.1708872 0.1385163 -0.005128085 0.171323 0.1388036 0.03766262 0.1712879 0.139738 0.01628637 0.1717218 0.1395864 -0.00494337 0.1718404 0.1396875 -0.005034327 0.1719922 0.1406553 0.03756356 0.1719915 0.1416494 0.03746408 0.1718329 0.1406392 -0.005540668 0.1702914 0.1380761 -0.00627321 0.1697842 0.1382421 -0.00677669 0.1644853 0.1369625 -0.006922721 0.1697588 0.1388443 -0.007757663 0.1641735 0.1382563 -0.00747615 0.1695152 0.1397377 -0.007921338 0.1639764 0.1391499 -0.007603704 0.1696137 0.1406691 -0.007368743 0.1625031 0.1364349 -0.007326841 0.1639384 0.1373426 -0.00620377 0.1640516 0.1364504 -0.006950616 0.1618782 0.1357581 -0.008058309 0.1629648 0.1380459 -0.008253872 0.1622792 0.1374979 0.04033702 0.164426 0.1741924 0.0408532 0.1636144 0.173379 0.04096871 0.1632817 0.174197 0.04041892 0.1646563 0.1734338 0.04131978 0.1630932 0.1735652 0.04010117 0.1642891 0.1746817 0.03964364 0.1641681 0.1751298 0.03907066 0.1644492 0.1754031 0.04135161 0.1627819 0.1744231 0.1628394 0.1245 0.1654331 0.1340229 0.1245 0.1495332 0.1632953 0.1245 0.1523784 0.04206168 0.1550424 0.1362372 0.04170113 0.1589478 0.148606 0.1825192 -0.03499996 0.1725 0.1771844 -0.03783017 0.1725 0.1822945 -0.03720569 0.1479209 0.1856028 -0.03388792 0.1725 0.172555 -0.0415433 0.1549693 0.1910662 -0.0348379 0.1528699 0.1943925 -0.03359621 0.1617212 0.1868023 -0.03521275 0.1550574 0.1867533 -0.0361191 0.1479354 0.1721633 -0.0418328 0.1478472 0.194 -0.03258204 0.1725 0.1887789 -0.03311014 0.1725 0.1944281 -0.03257864 0.1725 0.1578125 -0.05988901 0.1724604 0.1645635 -0.04980188 0.1724669 0.1680001 -0.04572623 0.1725 0.1723506 -0.04147356 0.1725 0.1560387 -0.05894082 0.1548914 0.1547811 -0.05837494 0.1477715 0.1635491 -0.04935705 0.1549188 0.1673599 -0.04563403 0.1549389 0.1627066 -0.04912883 0.1477969 0.1667256 -0.04562103 0.1478167 0.1881281 2.08897e-7 0.1475549 0.1865815 0.03618717 0.147831 0.1679999 0.04576766 0.1725 0.1651375 0.04817968 0.1568892 0.1723548 0.04150539 0.1724999 0.1772033 0.03784352 0.1725 0.1825538 0.03499996 0.1725 0.1675568 0.04582428 0.1569021 0.1856309 0.03388708 0.1724987 0.1888048 0.03310692 0.1724983 0.1722003 0.04199379 0.1569283 0.1668294 0.04587996 0.1478184 0.194 0.03258204 0.1725 0.1943925 0.03359621 0.1617212 0.1772406 0.03876012 0.1569581 0.1944281 0.03257864 0.1725 0.1717424 0.04239094 0.1478459 0.1769965 0.03949075 0.1478773 0.1857337 0.03529983 0.1570086 0.1910577 0.0348519 0.1528609 0.1888763 0.03461307 0.1570271 -0.04249995 -0.172 0.1383389 -0.0575 -0.1719999 0.1383579 -0.1635456 -0.03625714 0.165 -0.190915 -0.04232478 0.165 0.05750006 -0.1719999 0.1383714 0.04249995 -0.172 0.1383389 0.1683184 0.001999974 -0.09018957 0.1868985 0.001999974 -0.09135222 0.2036843 0.001999974 -0.08899289 0.221238 0.001999974 -0.08276063 0.2357773 0.001999974 -0.07399803 0.2495863 0.001999974 -0.06128442 0.2595135 0.001999974 -0.04753947 0.2666561 0.001999974 -0.03211975 0.2709553 0.001999974 -0.01393568 0.2714612 0.001999974 0.003086686 0.2682838 0.001999974 0.02133458 0.2621288 0.001999974 0.0370171 0.2530469 0.001999974 0.0512855 0.2430335 0.001999974 0.06208413 0.2431806 0.001999974 -0.05320894 0.2431806 0.001999974 0.05315226 0.2331806 0.001999974 -0.06320893 0.1268194 0.001999974 -0.06320893 0.1268194 0.001999974 0.06315225 0.1168194 0.001999974 0.05315226 0.2331806 0.001999974 0.06315225 0.1168194 0.001999974 -0.05320894 -0.1823164 -0.01047545 0.165 -0.1789587 -0.01038336 0.165 -0.1756647 -0.01104068 0.165 -0.1725996 -0.01241457 0.165 -0.169917 -0.014436 0.165 -0.1677516 -0.01700371 0.165 -0.1662117 -0.01998889 0.165 -0.1653748 -0.02324187 0.165 -0.1951643 -0.01228111 0.165 -0.1928495 -0.03238809 0.165 -0.1942672 -0.02236455 0.165 0.1121178 0.02799999 0.06788223 0.1266652 0.02799999 0.07982105 0.1001788 0.02799999 0.05333471 0.09130752 0.02799999 0.03673756 0.18 0.02799999 -0.09599995 0.1987287 0.02799999 -0.09415537 0.08584457 0.02799999 0.01872867 0.2167376 0.02799999 -0.08869242 0.08399999 0.02799999 0 0.2333347 0.02799999 -0.07982105 0.08584457 0.02799999 -0.01872867 0.2478822 0.02799999 -0.06788223 0.09130752 0.02799999 -0.03673756 0.2598211 0.02799999 -0.05333471 0.1001788 0.02799999 -0.05333471 0.2686924 0.02799999 -0.03673756 0.1121178 0.02799999 -0.06788223 0.1266652 0.02799999 -0.07982105 0.2741554 0.02799999 -0.01872867 0.1432624 0.02799999 -0.08869242 0.276 0.02799999 0 0.1612713 0.02799999 -0.09415537 0.2741554 0.02799999 0.01872867 0.2686924 0.02799999 0.03673756 0.2598211 0.02799999 0.05333471 0.2478822 0.02799999 0.06788223 0.2333347 0.02799999 0.07982105 0.2167376 0.02799999 0.08869242 0.1987287 0.02799999 0.09415537 0.18 0.02799999 0.09599995 0.1612713 0.02799999 0.09415537 0.1432624 0.02799999 0.08869242 -0.005115211 0.1719951 0.1736047 -0.006559789 0.1708793 0.1747319 -0.00520569 0.1707325 0.1753568 -0.004815757 0.1715905 0.1747733 -0.006964862 0.1710789 0.1737496 -0.00568813 0.171415 0.1747369 -0.005889236 0.1717782 0.1738316 -0.007661461 0.1696208 0.1695037 -0.007861971 0.1665238 0.1515374 -0.008995234 0.1651673 0.1524802 -0.008256554 0.1658806 0.1522809 -0.008127987 0.1668853 0.156535 -0.008912265 0.1669136 0.1623216 -0.008370637 0.1673952 0.1621947 -0.007940232 0.1679973 0.1617991 -0.007682502 0.16799 0.1519462 -0.007712423 0.1687547 0.1619458 -0.0517804 -0.172 0.1531946 -0.05188637 -0.172 0.1613345 -0.05369335 -0.172 0.1694183 -0.05178046 -0.172 0.1706945 -0.05503123 -0.172 0.1486093 -0.05440413 -0.172 0.1509348 -0.05489963 -0.172 0.1647923 -0.05485892 -0.172 0.1673101 -0.04999995 -0.172 0.1535 -0.04950213 -0.172 0.1609922 -0.04999995 -0.172 0.171 -0.04811364 -0.172 0.1531655 -0.04723179 -0.172 0.1617972 -0.04811358 -0.172 0.1706655 -0.04668438 -0.172 0.1522426 -0.04668438 -0.172 0.1697426 -0.04549419 -0.172 0.1507413 -0.04559576 -0.172 0.1635651 -0.04549419 -0.172 0.1682413 -0.05232357 -0.172 0.1440727 -0.05375802 -0.172 0.1451704 -0.05467504 -0.172 0.146727 -0.05071485 -0.172 0.1435186 -0.04496872 -0.172 0.1658907 -0.05331557 -0.172 0.1522426 -0.05375808 -0.172 0.1626704 -0.04496872 -0.172 0.1483907 -0.04559576 -0.172 0.1460651 -0.04668438 -0.172 0.1447574 -0.04831796 -0.172 0.1437569 0.04723173 -0.172 0.1527027 0.04950213 -0.172 0.1535078 0.04811358 -0.172 0.1613345 0.04559582 -0.172 0.1509349 0.04532492 -0.172 0.164227 0.04624187 -0.172 0.1626704 0.0470519 -0.172 0.1444214 0.04549419 -0.172 0.1462587 0.04496872 -0.172 0.1486093 0.04496872 -0.172 0.1661093 0.04928511 -0.172 0.1435186 0.05049782 -0.172 0.1609922 0.05188632 -0.172 0.1531655 0.05276817 -0.172 0.1617972 0.05119657 -0.172 0.1436453 0.05276817 -0.172 0.1442972 0.05375808 -0.172 0.1518296 0.05440419 -0.172 0.1635651 0.05467504 -0.172 0.150273 0.04559582 -0.172 0.1684349 0.04668438 -0.172 0.1697426 0.05446827 -0.172 0.1461549 0.0482195 -0.172 0.1706945 0.05502086 -0.172 0.1485 0.04999995 -0.172 0.171 0.05188632 -0.172 0.1706655 0.05331557 -0.172 0.1697426 0.05450576 -0.172 0.1682413 0.05503123 -0.172 0.1658906 0.03841531 0.1696678 0.175464 0.03929054 0.1694645 0.1751292 0.03988462 0.1695471 0.1744426 0.04010272 0.1695336 0.1737 0.03930991 0.1708083 0.174341 0.03886777 0.1704376 0.1750711 0.03739869 0.1719908 0.1737003 0.03830212 0.1715693 0.174341 0.03868007 0.1716011 0.1735081 0.0371803 0.1716983 0.1745703 0.03773134 0.1711035 0.1751391 0.03963172 0.1707174 0.1735184 -0.1851776 -0.01815986 0.1805 -0.183318 -0.01718384 0.1805 -0.1812789 -0.01668125 0.1805 -0.171517 -0.02532947 0.1805 -0.1717702 -0.02741432 0.1805 -0.1791787 -0.01668125 0.1805 -0.1725149 -0.02937805 0.1805 -0.1771396 -0.01718384 0.1805 -0.1737079 -0.03110647 0.1805 -0.17528 -0.01815986 0.1805 -0.17528 -0.03249913 0.1805 -0.1737079 -0.01955252 0.1805 -0.1771396 -0.0334751 0.1805 -0.1725149 -0.02128094 0.1805 -0.1717702 -0.02324461 0.1805 -0.1791787 -0.03397768 0.1805 -0.1812789 -0.03397768 0.1805 -0.183318 -0.0334751 0.1805 -0.1851776 -0.03249913 0.1805 -0.1867496 -0.03110647 0.1805 -0.1879427 -0.02937805 0.1805 -0.1886874 -0.02741432 0.1805 -0.1889406 -0.02532947 0.1805 -0.1886874 -0.02324461 0.1805 -0.1879427 -0.02128094 0.1805 -0.1867496 -0.01955252 0.1805 -0.01773023 0.04675078 0.1655 -0.006026804 0.04963541 0.1655 0.006026804 0.04963541 0.1655 0.04999995 0 0.1655 0.04854708 -0.01196575 0.1655 0.01773023 0.04675078 0.1655 0.04427278 -0.02323615 0.1655 0.02840322 0.04114913 0.1655 0.03742551 0.03315609 0.1655 0.03742551 -0.03315609 0.1655 0.04427278 0.02323615 0.1655 0.02840322 -0.04114913 0.1655 0.04854708 0.01196575 0.1655 0.01773023 -0.04675078 0.1655 0.006026804 -0.04963541 0.1655 -0.006026804 -0.04963541 0.1655 -0.01773023 -0.04675078 0.1655 -0.02840322 -0.04114913 0.1655 -0.03742551 -0.03315609 0.1655 -0.04427278 -0.02323615 0.1655 -0.04854708 -0.01196575 0.1655 -0.04999995 0 0.1655 -0.04854708 0.01196575 0.1655 -0.04427278 0.02323615 0.1655 -0.03742551 0.03315609 0.1655 -0.02840322 0.04114913 0.1655 0.04047763 0.1627974 0.1558763 0.04088634 0.1622202 0.160548 0.04097533 0.1596928 0.1483797 0.04136645 0.1565292 0.1386582 0.03878951 0.1707057 0.1397421 0.03876316 0.1713675 0.14063 0.03873658 0.1715672 0.1416364 0.03967213 0.170659 0.1416329 0.03962755 0.1703773 0.1406358 -0.007133305 0.1703805 0.139687 -0.007133841 0.1707156 0.140669 -0.006266951 0.171373 0.1396809 -0.006178081 0.1716024 0.1406655 -0.006305158 0.1707288 0.1388096 -0.001681268 0.172 0.1678975 -0.002538621 0.172 0.1663082 -3.57745e-4 0.172 0.1684907 8.40676e-4 0.172 0.1683716 -0.004653096 0.172 0.1616837 -0.002202033 0.172 0.1647824 -0.001177966 0.172 0.1637551 3.04457e-4 0.172 0.1634953 -0.001681327 0.172 0.1478974 -0.002538621 0.172 0.1463082 -3.57829e-4 0.172 0.1484907 8.40584e-4 0.172 0.1483716 0.001474142 0.172 0.1639608 0.002049326 0.172 0.14751 0.002252817 0.172 0.1648792 -0.002202033 0.172 0.1447824 -0.001178026 0.172 0.1437551 3.04443e-4 0.172 0.1434953 0.02624189 0.172 0.1693296 0.002049326 0.172 0.16751 0.0281136 0.172 0.1706655 0.001474201 0.172 0.1439608 0.02532488 0.172 0.167773 0.02496868 0.172 0.1658906 0.002515614 0.172 0.1660546 0.02559578 0.172 0.1635651 0.03276824 0.172 0.1702027 0.03049784 0.172 0.1710078 0.03440415 0.172 0.1684349 0.03503125 0.172 0.1661093 0.02668434 0.172 0.1622574 0.02821946 0.172 0.1613054 0.02624189 0.172 0.1518296 0.02811366 0.172 0.1531655 0.02532488 0.172 0.150273 0.02496868 0.172 0.1483907 0.002515614 0.172 0.1460546 0.02999997 0.172 0.161 0.03049784 0.172 0.1535078 0.03188639 0.172 0.1613345 0.002252817 0.172 0.1448792 0.02559578 0.172 0.1460651 0.03276818 0.172 0.1527027 0.03331559 0.172 0.1622574 0.03450578 0.172 0.1637587 0.02668434 0.172 0.1447574 0.03440415 0.172 0.1509348 0.02821946 0.172 0.1438054 0.02999997 0.172 0.1435 0.03188639 0.172 0.1438345 0.03331559 0.172 0.1447574 0.03450578 0.172 0.1462587 0.03503125 0.172 0.1486093 0.17 0.03499996 0.1725 0.17 -0.03499996 0.1725 0.194 -0.03499996 0.1725 0.1955657 0 0.1725 0.1955657 0 0.1613631 0.1923354 1.88475e-7 0.1525377 0.194 0.03499996 0.1725 0.2331806 0.003999948 -0.06320893 0.1268194 0.003999948 -0.06320893 0.1168194 0.003999948 -0.05320894 0.1168194 0.003999948 0.05315226 0.1268194 0.003999948 0.06315225 0.2331806 0.003999948 0.06315225 0.2431806 0.003999948 0.05315226 0.2431806 0.003999948 -0.05320894 0.1163938 0.02799999 -0.07064175 0.1116211 0.02799999 -0.06603276 0.1071814 0.02799999 -0.06110203 0.1214765 0.02799999 -0.07490664 0.1030965 0.02799999 -0.05587363 0.1268443 0.02799999 -0.07880657 0.09938627 0.02799999 -0.05037301 0.1324711 0.02799999 -0.08232253 0.09606885 0.02799999 -0.04462695 0.1383294 0.02799999 -0.08543747 0.09316027 0.02799999 -0.0386635 0.1443907 0.02799999 -0.08813613 0.09067475 0.02799999 -0.03251171 0.1506255 0.02799999 -0.0904054 0.08862447 0.02799999 -0.02620148 0.1570034 0.02799999 -0.09223425 0.08701932 0.02799999 -0.01976364 0.1667659 0.02799999 -0.09416711 0.08586716 0.02799999 -0.01322948 0.0851736 0.02799999 -0.006630897 0.1766825 0.02799999 -0.09499996 0.08494204 0.02799999 0 0.1833175 0.02799999 -0.09499996 0.0851736 0.02799999 0.006630897 0.1899363 0.02799999 -0.09453713 0.1965066 0.02799999 -0.09361374 0.08586716 0.02799999 0.01322948 0.08773207 0.02799999 0.02300488 0.2029966 0.02799999 -0.09223425 0.2093745 0.02799999 -0.0904054 0.2156093 0.02799999 -0.08813613 0.09067475 0.02799999 0.03251171 0.09316027 0.02799999 0.0386635 0.2216706 0.02799999 -0.08543747 0.09606885 0.02799999 0.04462695 0.2275289 0.02799999 -0.08232253 0.09938627 0.02799999 0.05037301 0.2331557 0.02799999 -0.07880657 0.1030965 0.02799999 0.05587363 0.2385235 0.02799999 -0.07490664 0.1071814 0.02799999 0.06110203 0.2436062 0.02799999 -0.07064175 0.1139439 0.02799999 0.06840455 0.2483789 0.02799999 -0.06603276 0.2528186 0.02799999 -0.06110203 0.1214765 0.02799999 0.07490664 0.2569035 0.02799999 -0.05587363 0.1268443 0.02799999 0.07880657 0.2606137 0.02799999 -0.05037301 0.1324711 0.02799999 0.08232253 0.2639312 0.02799999 -0.04462695 0.2668397 0.02799999 -0.0386635 0.1383294 0.02799999 0.08543747 0.1443907 0.02799999 0.08813613 0.2693252 0.02799999 -0.03251171 0.1537889 0.02799999 0.09140878 0.2722681 0.02799999 -0.02300423 0.1634933 0.02799999 0.09361374 0.2741328 0.02799999 -0.01322948 0.1700637 0.02799999 0.09453713 0.2748264 0.02799999 -0.006630897 0.2750579 0.02799999 0 0.1766825 0.02799999 0.09499996 0.1833175 0.02799999 0.09499996 0.2748264 0.02799999 0.006630897 0.1899363 0.02799999 0.09453713 0.2736476 0.02799999 0.016514 0.1997711 0.02799999 0.09301441 0.2713755 0.02799999 0.02620148 0.2093745 0.02799999 0.0904054 0.2693252 0.02799999 0.03251171 0.2156093 0.02799999 0.08813613 0.2668397 0.02799999 0.0386635 0.2216706 0.02799999 0.08543747 0.2639312 0.02799999 0.04462695 0.2275289 0.02799999 0.08232253 0.2606137 0.02799999 0.05037301 0.2569035 0.02799999 0.05587363 0.2331557 0.02799999 0.07880657 0.2385235 0.02799999 0.07490664 0.2528186 0.02799999 0.06110203 0.2483789 0.02799999 0.06603276 0.2436062 0.02799999 0.07064175 -0.007448911 0.1701301 0.1606973 -0.006647348 0.1713058 0.1693564 -0.00568062 0.1718311 0.162202 -0.007991135 0.168 0.1528392 -0.05411487 -0.162 0.1631597 -0.05487495 -0.162 0.1647984 -0.04939484 -0.162 0.1709843 -0.05496352 -0.162 0.1666027 -0.04723173 -0.162 0.1702027 -0.05450576 -0.162 0.1682413 -0.05294811 -0.162 0.1700785 -0.04559582 -0.162 0.1684349 -0.05119657 -0.162 0.1708547 -0.04496872 -0.162 0.1661093 -0.04549419 -0.162 0.1637586 -0.04668438 -0.162 0.1622574 -0.04811358 -0.162 0.1613345 -0.05049782 -0.162 0.1609922 -0.05276817 -0.162 0.1617972 -0.05411487 -0.162 0.1456597 -0.05487495 -0.162 0.1472984 -0.0493949 -0.162 0.1534842 -0.05496352 -0.162 0.1491027 -0.04723173 -0.162 0.1527027 -0.05450576 -0.162 0.1507413 -0.05294811 -0.162 0.1525785 -0.04559582 -0.162 0.1509349 -0.05119657 -0.162 0.1533547 -0.04496872 -0.162 0.1486093 -0.04549419 -0.162 0.1462587 -0.04668438 -0.162 0.1447574 -0.04811358 -0.162 0.1438344 -0.05049782 -0.162 0.1434922 -0.05276817 -0.162 0.1442972 0.04588502 -0.162 0.1631597 0.045125 -0.162 0.1647984 0.05060505 -0.162 0.1709843 0.04503643 -0.162 0.1666027 0.05276823 -0.162 0.1702027 0.04549419 -0.162 0.1682413 0.04705184 -0.162 0.1700785 0.05440413 -0.162 0.1684349 0.04880338 -0.162 0.1708547 0.05503123 -0.162 0.1661093 0.05450576 -0.162 0.1637586 0.05331557 -0.162 0.1622574 0.05188637 -0.162 0.1613345 0.04950213 -0.162 0.1609922 0.04723179 -0.162 0.1617972 0.04559576 -0.162 0.1460651 0.04496872 -0.162 0.1483907 0.04928511 -0.162 0.1534814 0.05168193 -0.162 0.153243 0.04549419 -0.162 0.1507413 0.05331557 -0.162 0.1522426 0.04705184 -0.162 0.1525785 0.05440413 -0.162 0.1509348 0.05504626 -0.162 0.1485 0.05444574 -0.162 0.1461668 0.05331557 -0.162 0.1447574 0.05178052 -0.162 0.1438054 0.04950213 -0.162 0.1434922 0.04723179 -0.162 0.1442972 0.02622288 0.162 0.1693464 0.02512502 0.162 0.1672015 0.03060507 0.162 0.1610157 0.02503645 0.162 0.1653973 0.03276813 0.162 0.1617972 0.02549421 0.162 0.1637587 0.02705186 0.162 0.1619214 0.03440415 0.162 0.1635651 0.0288034 0.162 0.1611453 0.03503125 0.162 0.1658907 0.03450572 0.162 0.1682413 0.03331559 0.162 0.1697426 0.03188633 0.162 0.1706655 0.02999997 0.162 0.171 0.02831798 0.162 0.1707431 0.02622288 0.162 0.1518464 0.02512502 0.162 0.1497015 0.03060507 0.162 0.1435157 0.02503645 0.162 0.1478973 0.03276813 0.162 0.1442972 0.02549421 0.162 0.1462587 0.02705192 0.162 0.1444214 0.03440415 0.162 0.1460651 0.0288034 0.162 0.1436453 0.03503125 0.162 0.1483907 0.03450572 0.162 0.1507413 0.03294807 0.162 0.1525785 0.03071486 0.162 0.1534814 0.02831804 0.162 0.1532431 -0.001888573 0.162 0.1676732 -0.002437472 0.162 0.1666007 -7.85417e-5 0.162 0.1634556 -0.002455592 0.162 0.1654511 0.001384198 0.162 0.1638988 -0.001746118 0.162 0.1641477 0.002202033 0.162 0.1647824 0.002515614 0.162 0.1659454 0.002252817 0.162 0.1671207 0.001474142 0.162 0.1680391 3.57752e-4 0.162 0.1684907 -8.4066e-4 0.162 0.1683716 -0.002351164 0.162 0.1469756 -7.85319e-5 0.162 0.1434556 -0.002455592 0.162 0.1454511 0.001384258 0.162 0.1438988 -0.001746118 0.162 0.1441477 0.002202033 0.162 0.1447824 0.002515614 0.162 0.1459453 0.002252817 0.162 0.1471207 0.001474201 0.162 0.1480391 3.57829e-4 0.162 0.1484907 -0.001112759 0.162 0.1482895 0.17 0.01278233 0.1875 0.17 0.03499996 0.1875 0.17 -0.01278233 0.1875 0.17 -0.01278233 0.2245 0.17 0.01278233 0.2245 0.17 -0.03499996 0.1875 0.194 0.03499996 0.1875 0.194 -0.03499996 0.1875 0.194 0.01458692 0.1875 0.194 -0.01458692 0.1875 0.194 -0.01458692 0.2245 0.194 0.01458692 0.2245 0.1700637 0.08199995 -0.09453713 0.1766825 0.08199995 -0.09499996 0.1833175 0.08199995 -0.09499996 0.1899363 0.08199995 -0.09453713 0.1965066 0.08199995 -0.09361374 0.2029966 0.08199995 -0.09223425 0.2093745 0.08199995 -0.0904054 0.2156093 0.08199995 -0.08813613 0.2216706 0.08199995 -0.08543747 0.2275289 0.08199995 -0.08232253 0.2331557 0.08199995 -0.07880657 0.2385235 0.08199995 -0.07490664 0.2436062 0.08199995 -0.07064175 0.2483789 0.08199995 -0.06603276 0.2528186 0.08199995 -0.06110203 0.2569035 0.08199995 -0.05587363 0.2606137 0.08199995 -0.05037301 0.2639312 0.08199995 -0.04462695 0.2681684 0.08199995 -0.03562188 0.2713755 0.08199995 -0.02620148 0.2729807 0.08199995 -0.01976364 0.2741328 0.08199995 -0.01322948 0.2748264 0.08199995 -0.006630897 0.2750346 0.08199995 0.003319919 0.2741328 0.08199995 0.01322948 0.2729807 0.08199995 0.01976364 0.2713755 0.08199995 0.02620148 0.2693252 0.08199995 0.03251171 0.2668397 0.08199995 0.0386635 0.2639312 0.08199995 0.04462695 0.2606137 0.08199995 0.05037301 0.2569035 0.08199995 0.05587363 0.2528186 0.08199995 0.06110203 0.2483789 0.08199995 0.06603276 0.2436062 0.08199995 0.07064175 0.2385235 0.08199995 0.07490664 0.2331557 0.08199995 0.07880657 0.2246431 0.08199995 0.08396172 0.2156093 0.08199995 0.08813613 0.2093745 0.08199995 0.0904054 0.2029966 0.08199995 0.09223425 0.1965066 0.08199995 0.09361374 0.1899363 0.08199995 0.09453713 0.1833175 0.08199995 0.09499996 0.1766825 0.08199995 0.09499996 0.1667659 0.08199995 0.09416711 0.1570034 0.08199995 0.09223425 0.1506255 0.08199995 0.0904054 0.1443907 0.08199995 0.08813613 0.1383294 0.08199995 0.08543747 0.1324711 0.08199995 0.08232253 0.1241062 0.08199995 0.07693159 0.1163938 0.08199995 0.07064175 0.1116211 0.08199995 0.06603276 0.1071814 0.08199995 0.06110203 0.1030965 0.08199995 0.05587363 0.09764742 0.08199995 0.0475462 0.09316027 0.08199995 0.0386635 0.09067475 0.08199995 0.03251171 0.08862447 0.08199995 0.02620148 0.08701932 0.08199995 0.01976364 0.08586716 0.08199995 0.01322948 0.0851736 0.08199995 0.006630897 0.08494204 0.08199995 0 0.0851736 0.08199995 -0.006630897 0.08586716 0.08199995 -0.01322948 0.08701932 0.08199995 -0.01976364 0.08862447 0.08199995 -0.02620148 0.09067475 0.08199995 -0.03251171 0.09316027 0.08199995 -0.0386635 0.09606885 0.08199995 -0.04462695 0.09938627 0.08199995 -0.05037301 0.1030965 0.08199995 -0.05587363 0.1071814 0.08199995 -0.06110203 0.1116211 0.08199995 -0.06603276 0.1163938 0.08199995 -0.07064175 0.1214765 0.08199995 -0.07490664 0.1268443 0.08199995 -0.07880657 0.1324711 0.08199995 -0.08232253 0.1383294 0.08199995 -0.08543747 0.1443907 0.08199995 -0.08813613 0.1537889 0.08199995 -0.09140878 0.1634933 0.08199995 -0.09361374 0.2163473 0.08199995 -0.07133549 0.2447713 0.08199995 -0.04705905 0.2482638 0.08199995 -0.04183208 0.221832 0.08199995 -0.06826382 0.2270591 0.08199995 -0.06477129 0.2319959 0.08199995 -0.0608794 0.2408794 0.08199995 -0.05199593 0.2366122 0.08199995 -0.05661219 0.1233878 0.08199995 0.05661219 0.1191205 0.08199995 0.05199593 0.1280041 0.08199995 0.0608794 0.1329409 0.08199995 0.06477129 0.1152287 0.08199995 0.04705905 0.1381679 0.08199995 0.06826382 0.1117362 0.08199995 0.04183208 0.1436527 0.08199995 0.07133549 0.1086645 0.08199995 0.03634721 0.1493617 0.08199995 0.07396739 0.1060326 0.08199995 0.03063827 0.1038568 0.08199995 0.02474039 0.1552596 0.08199995 0.0761432 0.16131 0.08199995 0.07784956 0.1021504 0.08199995 0.01868999 0.1674756 0.08199995 0.07907599 0.100924 0.08199995 0.01252436 0.1737183 0.08199995 0.07981491 0.1001851 0.08199995 0.006281554 0.18 0.08199995 0.08006167 0.09993827 0.08199995 0 0.1001851 0.08199995 -0.006281554 0.1862816 0.08199995 0.07981491 0.100924 0.08199995 -0.01252436 0.1925244 0.08199995 0.07907599 0.1986899 0.08199995 0.07784956 0.1021504 0.08199995 -0.01868999 0.1038568 0.08199995 -0.02474039 0.2047404 0.08199995 0.0761432 0.2106383 0.08199995 0.07396739 0.1060326 0.08199995 -0.03063827 0.2163473 0.08199995 0.07133549 0.1086645 0.08199995 -0.03634721 0.221832 0.08199995 0.06826382 0.1117362 0.08199995 -0.04183208 0.2270591 0.08199995 0.06477129 0.1152287 0.08199995 -0.04705905 0.2319959 0.08199995 0.0608794 0.1191205 0.08199995 -0.05199593 0.2366122 0.08199995 0.05661219 0.1233878 0.08199995 -0.05661219 0.2408794 0.08199995 0.05199593 0.1280041 0.08199995 -0.0608794 0.1329409 0.08199995 -0.06477129 0.2447713 0.08199995 0.04705905 0.1381679 0.08199995 -0.06826382 0.2482638 0.08199995 0.04183208 0.1436527 0.08199995 -0.07133549 0.2513355 0.08199995 0.03634721 0.1493617 0.08199995 -0.07396739 0.2539674 0.08199995 0.03063827 0.1552596 0.08199995 -0.0761432 0.2561432 0.08199995 0.02474039 0.2578496 0.08199995 0.01868999 0.16131 0.08199995 -0.07784956 0.259076 0.08199995 0.01252436 0.1674756 0.08199995 -0.07907599 0.2598149 0.08199995 0.006281554 0.1737183 0.08199995 -0.07981491 0.2600617 0.08199995 0 0.18 0.08199995 -0.08006167 0.1862816 0.08199995 -0.07981491 0.2598149 0.08199995 -0.006281554 0.1925244 0.08199995 -0.07907599 0.259076 0.08199995 -0.01252436 0.1986899 0.08199995 -0.07784956 0.2578496 0.08199995 -0.01868999 0.2047404 0.08199995 -0.0761432 0.2561432 0.08199995 -0.02474039 0.2539674 0.08199995 -0.03063827 0.2106383 0.08199995 -0.07396739 0.2513355 0.08199995 -0.03634721 0.1381679 0.11 -0.06826382 0.1436527 0.11 -0.07133549 0.1493617 0.11 -0.07396739 0.1552596 0.11 -0.0761432 0.16131 0.11 -0.07784956 0.1674756 0.11 -0.07907599 0.1737183 0.11 -0.07981491 0.18 0.11 -0.08006167 0.1862816 0.11 -0.07981491 0.1925244 0.11 -0.07907599 0.1986899 0.11 -0.07784956 0.2047404 0.11 -0.0761432 0.2106383 0.11 -0.07396739 0.2163473 0.11 -0.07133549 0.221832 0.11 -0.06826382 0.2270591 0.11 -0.06477129 0.2319959 0.11 -0.0608794 0.2366122 0.11 -0.05661219 0.2408794 0.11 -0.05199593 0.2447713 0.11 -0.04705905 0.2482638 0.11 -0.04183208 0.2513355 0.11 -0.03634721 0.2539674 0.11 -0.03063827 0.2561432 0.11 -0.02474039 0.2578496 0.11 -0.01868999 0.259076 0.11 -0.01252436 0.2598149 0.11 -0.006281554 0.2600617 0.11 0 0.2598149 0.11 0.006281554 0.259076 0.11 0.01252436 0.2578496 0.11 0.01868999 0.2561432 0.11 0.02474039 0.2539674 0.11 0.03063827 0.2513355 0.11 0.03634721 0.2482638 0.11 0.04183208 0.2447713 0.11 0.04705905 0.2408794 0.11 0.05199593 0.2366122 0.11 0.05661219 0.2319959 0.11 0.0608794 0.2270591 0.11 0.06477129 0.221832 0.11 0.06826382 0.2163473 0.11 0.07133549 0.2106383 0.11 0.07396739 0.2047404 0.11 0.0761432 0.1986899 0.11 0.07784956 0.1925244 0.11 0.07907599 0.1862816 0.11 0.07981491 0.18 0.11 0.08006167 0.1737183 0.11 0.07981491 0.1674756 0.11 0.07907599 0.16131 0.11 0.07784956 0.1552596 0.11 0.0761432 0.1493617 0.11 0.07396739 0.1436527 0.11 0.07133549 0.1381679 0.11 0.06826382 0.1329409 0.11 0.06477129 0.1280041 0.11 0.0608794 0.1233878 0.11 0.05661219 0.1191205 0.11 0.05199593 0.1152287 0.11 0.04705905 0.1117362 0.11 0.04183208 0.1086645 0.11 0.03634721 0.1060326 0.11 0.03063827 0.1038568 0.11 0.02474039 0.1021504 0.11 0.01868999 0.100924 0.11 0.01252436 0.1001851 0.11 0.006281554 0.09993827 0.11 0 0.1001851 0.11 -0.006281554 0.100924 0.11 -0.01252436 0.1021504 0.11 -0.01868999 0.1038568 0.11 -0.02474039 0.1060326 0.11 -0.03063827 0.1086645 0.11 -0.03634721 0.1117362 0.11 -0.04183208 0.1152287 0.11 -0.04705905 0.1191205 0.11 -0.05199593 0.1233878 0.11 -0.05661219 0.1280041 0.11 -0.0608794 0.1329409 0.11 -0.06477129 0.1468439 0.11 -0.03742551 0.1388508 0.11 -0.02840322 0.1567638 0.11 -0.04427278 0.1332492 0.11 -0.01773023 0.1680341 0.11 -0.04854708 0.1303645 0.11 -0.006026804 0.18 0.11 -0.04999995 0.1303645 0.11 0.006026804 0.1919658 0.11 -0.04854708 0.1332492 0.11 0.01773023 0.2032362 0.11 -0.04427278 0.1388508 0.11 0.02840322 0.2131561 0.11 -0.03742551 0.1468439 0.11 0.03742551 0.2211492 0.11 -0.02840322 0.1567638 0.11 0.04427278 0.2267508 0.11 -0.01773023 0.1680341 0.11 0.04854708 0.2296354 0.11 -0.006026804 0.18 0.11 0.04999995 0.2296354 0.11 0.006026804 0.1919658 0.11 0.04854708 0.2267508 0.11 0.01773023 0.2032362 0.11 0.04427278 0.2211492 0.11 0.02840322 0.2131561 0.11 0.03742551 0.1332492 0.12 0.01773023 0.1303645 0.12 0.006026804 0.1388508 0.12 0.02840322 0.18 0.12 0.04999995 0.1468439 0.12 0.03742551 0.1919658 0.12 0.04854708 0.1567638 0.12 0.04427278 0.2032362 0.12 0.04427278 0.1680341 0.12 0.04854708 0.2131561 0.12 0.03742551 0.2211492 0.12 0.02840322 0.2267508 0.12 0.01773023 0.2296354 0.12 0.006026804 0.2296354 0.12 -0.006026804 0.2267508 0.12 -0.01773023 0.2211492 0.12 -0.02840322 0.2131561 0.12 -0.03742551 0.2032362 0.12 -0.04427278 0.1919658 0.12 -0.04854708 0.18 0.12 -0.04999995 0.1680341 0.12 -0.04854708 0.1567638 0.12 -0.04427278 0.1468439 0.12 -0.03742551 0.1388508 0.12 -0.02840322 0.1332492 0.12 -0.01773023 0.1303645 0.12 -0.006026804 + + + + + + + + + + 0 0 -1 -1.16722e-6 0 -1 -1.16722e-6 0 -1 2.52901e-6 0 -1 1.16722e-6 0 -1 -3.70348e-7 0 -1 -5.05802e-6 0 -1 6.83146e-7 0 -1 3.4691e-7 0 -1 6.32252e-7 0 -1 2.04387e-6 0 -1 -2.04387e-6 0 -1 3.95424e-7 0 -1 -5.10967e-7 0 -1 -6.83146e-7 0 -1 -2.04387e-6 0 -1 3.79351e-6 0 -1 -3.76135e-7 0 -1 -1.16722e-6 0 -1 1.16722e-6 0 -1 0 0 -1 0 0 -1 -9.93909e-7 0 -1 3.76135e-7 0 -1 -1.4196e-6 0 -1 -3.79351e-6 0 -1 9.93909e-7 0 -1 1.4196e-6 0 -1 1.16722e-6 0 -1 -0.9723703 -0.2334441 3.18212e-5 -0.9723454 -0.2335479 2.39997e-5 -0.9969174 -0.07846009 -1.98357e-5 -0.9969391 -0.07818269 0 -0.9969173 0.07845985 0 -0.9969172 0.07846164 0 -0.9723703 0.2334442 -1.60791e-4 -0.9729067 0.2311984 0 -0.9238799 0.3826829 -5.42542e-5 -0.9255849 0.3785402 2.76868e-4 -0.8526409 0.5224975 5.77874e-6 -0.8533179 0.5213911 1.08211e-4 -0.7604056 0.6494486 0 -0.7603021 0.6495696 -1.34142e-5 -0.6494479 0.7604061 0 -0.6494484 0.7604057 0 -0.522498 0.8526406 2.53992e-5 -0.5222805 0.8527739 0 -0.3826835 0.9238796 0 -0.3817911 0.9242487 -1.04622e-4 -0.233445 0.9723701 0 -0.2334451 0.97237 0 -0.07846045 0.9969173 -7.65438e-6 -0.07851856 0.9969127 0 0.07846045 0.9969173 0 0.07886022 0.9968857 -5.71401e-5 0.2334451 0.9723701 0 0.2334451 0.9723701 0 0.3826833 0.9238797 -9.9881e-5 0.3821182 0.9241136 0 0.5224984 0.8526404 0 0.521785 0.8530771 1.4689e-4 0.6494483 0.7604057 0 0.649448 0.7604061 0 0.7604058 0.6494483 0 0.760406 0.649448 0 0.8526401 0.5224986 0 0.8526405 0.5224981 0 0.92388 0.3826823 -1.95972e-4 0.9235102 0.3835739 0 0.9723701 0.2334449 0 0.9722628 0.2338914 9.57783e-5 0.9969173 0.07846117 0 0.9969173 0.07846033 0 0.9969173 -0.07846117 0 0.9969174 -0.07845973 0 0.9723698 -0.2334461 0 0.9723704 -0.2334437 0 0.9238794 -0.3826838 0 0.9238793 -0.3826839 0 0.8526405 -0.5224983 0 0.8526407 -0.5224977 0 0.760406 -0.6494481 0 0.7599898 -0.649935 1.24603e-4 0.649448 -0.7604061 -8.53033e-5 0.6490978 -0.760705 0 0.5224984 -0.8526404 0 0.5224979 -0.8526406 0 0.3826836 -0.9238795 0 0.3826833 -0.9238796 0 0.2334451 -0.9723701 0 0.2320123 -0.9727128 2.3126e-4 0.07846045 -0.9969173 -1.91021e-4 0.07712888 -0.9970212 0 -0.07846045 -0.9969173 0 -0.07846045 -0.9969173 0 -0.233445 -0.97237 0 -0.2338478 -0.9722732 5.12746e-5 -0.3826835 -0.9238795 -4.48537e-5 -0.383051 -0.9237272 0 -0.5224981 -0.8526405 0 -0.5224984 -0.8526403 0 -0.649448 -0.7604061 0 -0.649097 -0.7607057 -4.38488e-5 -0.7604058 -0.6494483 -8.97429e-6 -0.7604731 -0.6493695 0 -0.8526405 -0.5224982 0 -0.8509962 -0.5251719 -2.53877e-4 -0.92388 -0.3826823 9.93907e-5 -0.9227954 -0.3852903 -1.22009e-4 0.7071087 0.7071049 0 0.7071062 0.7071075 0 0 1 0 -0.7071087 0.7071049 0 -0.7071062 0.7071075 0 -1 0 0 -0.7071045 0.7071092 0 -0.7071089 0.7071048 0 -0.7071081 0.7071055 0 -0.7071055 0.7071081 0 -0.7071081 -0.7071055 0 -0.7071055 -0.7071081 0 0 -1 0 -0.7071048 -0.7071089 0 -0.7071086 -0.707105 0 -0.7071087 -0.7071049 0 -0.7071062 -0.7071075 0 0.7071087 -0.7071049 0 0.7071062 -0.7071075 0 1 0 0 0.7071045 -0.7071092 0 0.7071089 -0.7071048 0 0.7071081 -0.7071055 0 0.7071055 -0.7071081 0 0.7071081 0.7071055 0 0.7071055 0.7071081 0 0.7071048 0.7071089 0 0.7071086 0.707105 0 -0.1825866 0.7415817 -0.6455377 -0.2937723 0.9283962 -0.2275487 -0.3921175 0.1516013 -0.9073373 -0.3074373 0.920803 -0.2400089 -0.684081 0.4150833 -0.5997825 -0.6837611 0.4117555 -0.6024353 -0.3060375 0.5977112 -0.741001 -0.6258568 0.4743795 -0.619086 -0.6580141 0.4545824 -0.6003103 -0.6237921 0.5707212 -0.5340046 -0.3764292 0.3535694 -0.8563234 -0.627419 0.561697 -0.5392976 -0.4923943 0.7664968 -0.4123475 -0.3988131 0.2553648 -0.8807593 -0.4980293 0.7585071 -0.4202784 -0.3844435 0.1998641 -0.9012534 -0.3009653 0.9066913 -0.2955181 -0.2996826 0.9086656 -0.2907185 -0.6223359 0.5036247 -0.5992164 -0.2679637 0.6362892 -0.7234166 -0.2182114 0.7013834 -0.6785611 -0.6423801 0.495568 -0.5846025 -0.3568431 0.4032605 -0.8426411 -0.7978625 0.0489735 -0.6008471 -0.2225173 0.9435434 -0.2453816 -0.3518581 0.4426137 -0.8247964 -0.5762057 0.6317268 -0.5185638 -0.576399 0.6313133 -0.5188524 -0.3996431 0.3108977 -0.8623388 -0.5975406 0.5580031 -0.5758278 -0.2684463 0.6581944 -0.703361 -0.2501086 0.6875352 -0.6817192 -0.3907142 0.1839378 -0.9019476 -0.3675877 0.1790763 -0.9125848 -0.4150919 0.8246759 -0.3841987 -0.4226663 0.8167024 -0.3928747 -0.3987006 0.2553153 -0.8808246 -0.1200854 0.9598846 -0.2533793 -0.1278293 0.9629418 -0.2374927 -0.2156897 0.942341 -0.2558739 -0.527566 0.6857034 -0.5014827 -0.3938893 0.3605914 -0.8454733 -0.5304548 0.6814545 -0.5042196 -0.3363807 0.5023223 -0.7965679 -0.3690832 0.851734 -0.3719233 -0.3597328 0.8589829 -0.3643361 -0.3197075 0.5315693 -0.7843605 -0.3884218 0.3088304 -0.868189 -0.5602439 0.6057314 -0.5649923 -0.5733867 0.5409514 -0.6153042 -0.6019734 0.5356786 -0.5921795 -0.4776524 0.7372781 -0.4777753 -0.4866161 0.7244009 -0.4883115 -0.2979393 0.588488 -0.7516077 -0.3947215 0.4135471 -0.8204717 -0.3036129 0.8865213 -0.3491407 -0.291089 0.5972822 -0.7473428 -0.2927176 0.894808 -0.3370981 -0.3945472 0.1454131 -0.9072968 -0.3482796 0.2251573 -0.9099482 -0.3935589 0.3604148 -0.8457026 -0.4146488 0.2487419 -0.875325 -0.4413793 0.7633975 -0.4716024 -0.3897777 0.5039653 -0.770774 -0.4019655 0.5105006 -0.76014 -0.4291446 0.4803183 -0.7649374 -0.4004729 -0.01381468 -0.9162045 -0.393126 0.4131867 -0.8214188 -0.4055128 0.275157 -0.8716926 -0.5453252 0.5977162 -0.5876697 -0.425907 0.2843661 -0.8589175 -0.5456187 0.6111629 -0.5733936 -0.4613192 0.7147726 -0.525628 -0.4327136 0.3404267 -0.8347866 -0.4467652 0.3450037 -0.8254535 -0.3874137 0.4628195 -0.7973136 -0.4360526 0.317068 -0.8422151 -0.4383613 0.316942 -0.8410632 -0.4038762 0.7935074 -0.4552254 -0.3993449 0.7985209 -0.450431 -0.1483579 0.9449149 -0.2917633 -0.2223912 0.9212229 -0.3192028 -0.1268313 0.9346683 -0.332128 -0.2093752 0.9284522 -0.3068202 -0.5035631 0.658218 -0.5596189 -0.5041663 0.6571978 -0.5602745 -0.4294412 0.7504938 -0.5023339 -0.5155079 0.5974102 -0.6142905 -0.352679 0.8291165 -0.4338011 -0.363024 0.8200492 -0.4424173 -0.394539 0.7688729 -0.5031635 -0.4896343 0.6395083 -0.5926951 -0.4607861 0.7006825 -0.5447204 -0.4601325 0.7017012 -0.5439611 -0.289873 0.8653314 -0.4088709 -0.2965864 0.8594528 -0.4163861 -0.3409431 0.8110494 -0.4753491 -0.9518936 0.07608962 -0.2968316 -0.4197442 0.7305346 -0.538641 -0.8978606 0.3794258 0.2233435 -0.9533235 0.0715624 -0.2933483 -0.9292443 0.2335361 -0.2862973 -0.9291964 0.229421 -0.2897591 -0.4345247 0.6731985 -0.5983245 -0.7791441 0.6028232 -0.1718683 -0.9037678 0.3207547 -0.2834084 -0.8765069 0.3916939 -0.2798422 -0.9040395 0.3197836 -0.2836393 -0.3848897 0.7648333 -0.516614 -0.3832532 0.7676252 -0.5136814 -0.8927068 0.05053365 -0.4477959 -0.9037575 0.07803612 -0.4208715 -0.2879184 0.8409447 -0.458165 -0.2862678 0.8442637 -0.4530667 -0.2169687 0.8963503 -0.3866275 -0.1508274 0.9206126 -0.3601716 -0.2107673 0.9003079 -0.3808189 -0.87769 0.38983 -0.2787345 -0.1497318 0.9201829 -0.3617235 -0.8270122 0.4957917 -0.2650311 -0.3431343 0.7953264 -0.4997146 -0.3496333 0.7887844 -0.5055451 -0.8663026 0.0697546 -0.4946253 -0.2820298 0.8304735 -0.4803884 -0.8829934 0.2171316 -0.4161453 -0.8838828 0.2217553 -0.411796 -0.8600267 0.3091929 -0.4058988 -0.8611269 0.3042457 -0.4073022 -0.2137248 0.8769388 -0.4304648 -0.6338951 0.7695397 0.07736772 -0.2861444 0.8300402 -0.4787011 -0.8236249 0.4996585 -0.2682973 -0.4517787 0.6709432 -0.5879892 -0.8439289 0.2104912 -0.4934343 -0.239934 0.8498478 -0.4692445 -0.845999 0.2125971 -0.4889666 -0.3989276 0.7180419 -0.5703269 -0.4143097 0.6999074 -0.581788 -0.2027671 0.8743762 -0.4408535 -0.8314268 0.2964952 -0.469915 -0.1388787 0.896739 -0.4202048 -0.2088836 0.8680136 -0.4504664 -0.7623267 0.5948244 -0.2550334 -0.3663026 0.7435327 -0.5594477 -0.3641291 0.7461062 -0.5574365 -0.7562521 0.605726 -0.2473438 -0.1813076 0.8486974 -0.4968304 -0.233675 0.8319384 -0.5032641 -0.8379645 0.3703951 -0.4007779 -0.83748 0.376128 -0.3964279 -0.3918597 0.6901244 -0.6084195 -0.8347713 0.06642156 -0.5465758 -0.784106 0.1456086 -0.6033043 -0.3250939 0.7772181 -0.5387451 -0.83582 0.06895983 -0.5446553 -0.8029655 0.06573599 -0.5923895 -0.3322787 0.7690854 -0.545984 -0.2746263 0.8094958 -0.5189384 -0.2741711 0.8096137 -0.5189952 -0.7086996 0.6646618 -0.2365792 -0.3565632 0.7225198 -0.5923073 -0.6499164 0.7244084 -0.2298722 -0.7146088 0.6564353 -0.2417171 -0.8023589 0.3503098 -0.4832218 -0.3060456 0.7384618 -0.6008414 -0.3112256 0.7678108 -0.5600047 -0.8065654 0.3598424 -0.4690051 -0.4483594 0.8922193 -0.05402493 -0.267207 0.7982758 -0.5397744 -0.2602098 0.7979034 -0.5437289 -0.7903187 0.4757135 -0.3861258 -0.7892154 0.4826738 -0.3796908 -0.1995303 0.846228 -0.4940505 -0.1673219 0.9247276 -0.3418807 -0.3119075 0.7575577 -0.5734284 -0.2913929 0.7330889 -0.6145495 -0.6540845 0.7214706 -0.2272744 -0.3182329 0.7396326 -0.593019 -0.8172589 0.2039186 -0.5389853 -0.2541691 0.7848847 -0.5651143 -0.8183045 0.2075319 -0.5360115 -0.2519869 0.78726 -0.5627825 -0.7628866 0.4628825 -0.4513799 -0.7616092 0.4596112 -0.4568468 -0.1869044 0.8247157 -0.5337703 -0.1209182 0.8547052 -0.5048345 -0.1892183 0.8227306 -0.5360139 -0.1132326 0.8556255 -0.5050577 -0.7313871 0.5769906 -0.3635309 -0.7344401 0.5697962 -0.368687 -0.2411617 0.7691997 -0.5917541 -0.2362284 0.7535062 -0.6135346 -0.2454698 0.7627652 -0.5982758 -0.1789996 0.8082965 -0.5609066 -0.1204546 0.8371328 -0.5335724 -0.5903685 0.7765219 -0.2201796 -0.1803552 0.8067871 -0.5626426 -0.1046707 0.834856 -0.5404253 -0.5757518 0.7902385 -0.2098407 -0.2259711 0.7356157 -0.6385974 -0.2276995 0.7566075 -0.6129422 -0.1728222 0.7940968 -0.5827029 -0.1176084 0.823169 -0.5554828 -0.1783605 0.7887665 -0.5882475 -0.6910927 0.6294968 -0.3551405 -0.1525245 0.7591633 -0.6327776 -0.6870803 0.6368573 -0.349762 -0.7098576 0.5552312 -0.4333828 -0.7097858 0.5514676 -0.4382782 -0.4560937 0.1904909 -0.8693054 -0.2817533 0.9484665 -0.1450048 -0.5253203 0.8259404 -0.2045997 -0.5174717 0.8326059 -0.1974602 -0.4055182 0.06752669 -0.9115894 -0.7809443 0.3383139 -0.5250425 -0.4386001 0.3333424 -0.8345735 -0.781171 0.3433782 -0.5214053 -0.2313091 0.9644393 -0.1278793 -0.1940742 0.9760365 0.09842765 -0.4146205 0.2289049 -0.8807341 -0.4694605 0.8630848 -0.1862569 -0.2137814 0.6632582 -0.7172073 -0.6694418 0.6107497 -0.422886 -0.2458108 0.6943545 -0.6763496 -0.6690821 0.6142299 -0.4183908 -0.6354329 0.6937129 -0.3390982 -0.6305726 0.7018162 -0.3314095 -0.1473045 0.9800778 -0.1332255 -0.08598738 0.9928038 -0.08334779 -0.1724482 0.9773323 -0.1228135 -0.4053607 0.06806021 -0.9116198 -0.7829418 0.1979911 -0.5897473 -0.7866379 0.2142534 -0.5790479 -0.4180268 0.8909209 -0.1775208 -0.4351518 0.8804383 -0.1883378 -0.7384218 0.4426416 -0.5087255 -0.08356297 0.8165058 -0.5712578 -0.7379824 0.4483599 -0.5043365 -0.1055586 0.8092997 -0.5778335 -0.1944416 0.7564786 -0.624446 -0.1947209 0.7559803 -0.6249622 -0.3695442 0.001085996 -0.9292126 -0.7186587 0.2151551 -0.6612398 -0.5713466 0.758054 -0.3145114 -0.5781204 0.7501372 -0.321047 -0.3878787 0.3814734 -0.839064 -0.7634235 0.2617366 -0.5904902 -0.616936 0.6786693 -0.3984947 -0.6172451 0.6745185 -0.4050103 -0.3539616 0.5009087 -0.7898111 -0.3980365 0.1612883 -0.9030799 -0.3624766 0.9181442 -0.1600692 -0.3727797 0.9127199 -0.1672661 -0.7400523 0.2669534 -0.6172994 -0.373238 0.4089984 -0.8327148 -0.2879456 0.9456424 -0.1511553 -0.5632413 0.7310298 -0.3851686 -0.5618321 0.7348681 -0.3798866 -0.3887013 0.07424217 -0.9183679 -0.3097497 0.5706771 -0.760515 -0.6879282 0.5384943 -0.4865992 -0.6900272 0.5322455 -0.4904868 -0.5096322 0.8088217 -0.2933981 -0.5172886 0.8000639 -0.3038261 -0.3582396 0.04875689 -0.9323558 -0.3553368 0.4549059 -0.8165761 -0.3471483 0.4880765 -0.8007931 -0.7468303 0.3275378 -0.5787604 -0.7470104 0.3303572 -0.5769226 -0.2289268 0.9492935 -0.2154863 -0.3102406 0.9506161 -0.008940696 -0.719655 0.3226988 -0.6147863 -0.4000258 0.1540003 -0.9034729 -0.7232333 0.3218389 -0.6110264 -0.6521241 0.5898661 -0.476227 -0.3939587 0.2243641 -0.8913233 -0.6491518 0.5965103 -0.4719931 -0.5044342 0.7864719 -0.3563819 -0.5057949 0.7811831 -0.3659571 -0.4336631 0.8568479 -0.2788338 -0.4238362 0.8651764 -0.2680165 -0.3727463 0.09595954 -0.9229583 -0.3808236 0.09728676 -0.9195156 -0.706479 0.4280546 -0.5636106 -0.7066233 0.425023 -0.5657199 -0.3748155 0.890144 -0.2591471 -0.3069599 0.5711745 -0.7612722 -0.3621339 0.8981684 -0.2493042 -0.5995916 0.6599727 -0.4526876 -0.2805464 0.6413171 -0.7141471 -0.2797951 0.6454776 -0.7106851 -0.6031624 0.6525368 -0.4586838 -0.3991115 0.2046935 -0.8937621 -0.3807191 0.3116323 -0.8705965 -0.4260016 0.8386105 -0.3394923 -0.423511 0.8438785 -0.3294047 -0.2628593 0.6275761 -0.7328393 -0.5523535 0.7083647 -0.4394602 -0.5471053 0.7156823 -0.4341368 -0.3830977 0.3019152 -0.8729739 -0.6586316 0.514142 -0.54942 -0.6578626 0.516458 -0.5481679 -0.3696688 0.8734144 -0.3170054 -0.2178572 0.7027337 -0.6772767 -0.3660141 0.8778247 -0.3089621 -0.9736935 -0.08807379 -0.2101528 -0.4780578 -0.7135578 -0.5121485 -0.4783302 -0.7129403 -0.5127539 -0.5505306 -0.6004211 -0.5800091 -0.5519331 -0.5956849 -0.583549 -0.5356702 -0.5853781 -0.6085968 -0.4217814 -0.763568 -0.4889422 -0.4478226 -0.7460087 -0.4928753 -0.4287818 -0.7607579 -0.4872306 -0.7978807 -0.04850733 -0.6008608 -0.509167 -0.6509356 -0.5630559 -0.5034624 -0.6347751 -0.5861625 -0.508544 -0.6524174 -0.5619027 -0.3410752 -0.8628682 -0.3729963 -0.3539142 -0.8472762 -0.3960653 -0.2284024 -0.9168819 -0.3273528 -0.2119185 -0.9196077 -0.3307752 -0.4653854 -0.7028173 -0.538019 -0.4699757 -0.6925959 -0.5472056 -0.4838472 -0.6368514 -0.6002601 -0.4208489 -0.74331 -0.5199775 -0.4179459 -0.7479382 -0.5156644 -0.4535244 -0.6721719 -0.5852355 -0.4513947 -0.6914573 -0.5640298 -0.3423045 -0.8242865 -0.450976 -0.2237949 -0.8918452 -0.3931006 -0.3406721 -0.8318229 -0.438193 -0.3770973 -0.6950613 -0.6121171 -0.4125868 -0.7279417 -0.5476068 -0.4099805 -0.7332378 -0.5424743 -0.3346731 -0.8154129 -0.4723301 -0.2188104 -0.8850741 -0.4108111 -0.1982818 -0.8893992 -0.4118899 -0.3368028 -0.8100339 -0.4800093 -0.3323072 -0.7952896 -0.5070371 -0.4149589 -0.7154263 -0.562116 -0.3877851 -0.6930788 -0.6076714 -0.4173398 -0.6961755 -0.5840952 -0.3214215 -0.7902826 -0.521672 -0.2231686 -0.850712 -0.4759045 -0.3269902 -0.776088 -0.5392262 -0.3041048 -0.7527592 -0.5838442 -0.2057919 -0.8541899 -0.4775033 -0.3224649 -0.7391755 -0.5913003 -0.3302064 -0.7537159 -0.568222 -0.2314323 -0.8235906 -0.5178201 -0.3111894 -0.7387369 -0.5978537 -0.2246901 -0.8065356 -0.5468224 -0.3170692 -0.7084568 -0.6305205 -0.2179687 -0.8091498 -0.5456798 -0.369451 -0.618035 -0.6939299 -0.343697 -0.5917733 -0.7291617 -0.4125102 -0.04857212 -0.9096572 -0.3999585 -0.01338499 -0.9164355 -0.258516 -0.7565856 -0.6006228 -0.3152344 -0.7069129 -0.6331678 -0.3210874 -0.6773062 -0.6619361 -0.4096739 -0.1445735 -0.900703 -0.4056252 -0.08802664 -0.9097909 -0.4136893 -0.4577701 -0.7869611 -0.4272266 -0.3535343 -0.8321605 -0.4269273 -0.2475443 -0.8697443 -0.9513101 -0.08371496 -0.2966495 -0.3696699 -7.88544e-4 -0.9291628 -0.9733077 -0.08823305 -0.2118657 -0.3598286 -0.0335915 -0.9324136 -0.3867445 -0.02573752 -0.9218277 -0.9625532 -0.2671496 -0.04607224 -0.9546527 -0.2099564 -0.2110843 -0.9326635 -0.295301 -0.2072104 -0.4145961 -0.1305375 -0.9005943 -0.9001553 -0.4353471 -0.01390761 -0.8947245 -0.3969322 -0.2047266 -0.9420917 -0.1077851 -0.317562 -0.8921051 -0.06243658 -0.4474935 -0.4114071 -0.3261585 -0.8510964 -0.4122706 -0.2934007 -0.8625248 -0.8567805 -0.4757187 -0.199045 -0.9269819 -0.2057018 -0.313674 -0.3793598 -0.5245501 -0.7621899 -0.3693704 -0.5747904 -0.7301929 -0.9276884 -0.1995118 -0.3155778 -0.7994632 -0.5681408 -0.1951276 -0.9066416 -0.2889901 -0.3073855 -0.9077488 -0.2819639 -0.310626 -0.7168141 -0.6701602 -0.1925176 -0.3952833 -0.4511928 -0.8001102 -0.4021915 -0.4048677 -0.8211725 -0.6668212 -0.7354152 -0.1204742 -0.3970193 -0.4472057 -0.8014879 -0.8738414 -0.380685 -0.302457 -0.8717258 -0.3887234 -0.298309 -0.3837995 -0.0723555 -0.9205774 -0.3883621 -0.08682692 -0.9174073 -0.3678269 -0.07239371 -0.927072 -0.834814 -0.06565058 -0.5466039 -0.8645034 -0.105461 -0.4914386 -0.808075 -0.08302944 -0.5831991 -0.3934069 -0.2884477 -0.8729428 -0.4059755 -0.1886231 -0.8942065 -0.4094306 -0.2321074 -0.8823224 -0.8393192 -0.4574621 -0.2937206 -0.8356222 -0.4661017 -0.290663 -0.4040108 -0.4087896 -0.8183315 -0.3754898 -0.5219651 -0.765872 -0.3845149 -0.4840922 -0.7860046 -0.8529797 -0.1898282 -0.4862007 -0.8533527 -0.1825084 -0.4883441 -0.5647814 -0.8096977 0.1594102 -0.3493968 -0.6016914 -0.7182544 -0.3014457 -0.7101867 -0.6362118 -0.2454056 -0.7454406 -0.6197535 -0.3187749 -0.6755584 -0.6648334 -0.787024 -0.5480276 -0.2833003 -0.390253 -0.1295878 -0.9115425 -0.7796379 -0.5649682 -0.2701401 -0.837451 -0.2584968 -0.4815136 -0.8368946 -0.2669443 -0.477858 -0.4202117 -0.2356254 -0.8763007 -0.4661069 -0.8844035 -0.02398109 -0.7108373 -0.6537758 -0.2593989 -0.3623492 -0.100406 -0.9266184 -0.7159572 -0.6464064 -0.2637503 -0.4088557 -0.2748164 -0.8702374 -0.8086229 -0.360041 -0.4652952 -0.3948488 -0.3558402 -0.8470374 -0.8101443 -0.3502898 -0.4700674 -0.3986421 -0.3434836 -0.8503549 -0.3561594 -0.6060431 -0.71124 -0.3398956 -0.6258657 -0.7019709 -0.3608639 -0.5448603 -0.7569045 -0.6528159 -0.7144721 -0.2517163 -0.3713775 -0.1290392 -0.9194714 -0.637968 -0.7310322 -0.2420512 -0.3898004 -0.1316936 -0.9114342 -0.3947371 -0.1862186 -0.8997251 -0.7821801 -0.4225285 -0.4578906 -0.7787053 -0.4329288 -0.4540824 -0.3948764 -0.4057837 -0.8242647 -0.4181548 -0.3120231 -0.8531051 -0.7919917 -0.1748518 -0.5849581 -0.7930922 -0.1439556 -0.5918459 -0.594976 -0.7681686 -0.2364756 -0.3975909 -0.2308607 -0.8880455 -0.3710579 -0.1649278 -0.9138461 -0.3987212 -0.1681858 -0.9015181 -0.5855214 -0.7773721 -0.2299071 -0.3675148 -0.601569 -0.7092586 -0.3319612 -0.6211846 -0.7098814 -0.3736406 -0.5015717 -0.7802683 -0.3812428 -0.5561842 -0.7384532 -0.5151894 -0.8300991 -0.2133438 -0.5310848 -0.81743 -0.2230634 -0.753535 -0.3331127 -0.5667637 -0.7793403 -0.2466749 -0.5760037 -0.7794042 -0.2302778 -0.5826674 -0.4184765 -0.3517603 -0.8373423 -0.3860885 -0.4475526 -0.8066179 -0.7386663 -0.5086668 -0.4423012 -0.735262 -0.5210955 -0.4334157 -0.7500944 -0.2341958 -0.6184747 -0.4809027 -0.8522142 -0.206067 -0.3887031 -0.2696352 -0.8810261 -0.4341251 -0.8795164 -0.1949012 -0.4648375 -0.8610387 -0.2062487 -0.4126911 -0.2093679 -0.8864825 -0.3620068 -0.2023901 -0.9099392 -0.3768994 -0.9069568 -0.1880863 -0.4039386 -0.3073017 -0.8616259 -0.671835 -0.6172327 -0.409465 -0.4248534 -0.4607215 -0.7792532 -0.3923425 -0.514576 -0.7624166 -0.6789345 -0.6035441 -0.41807 -0.4101487 -0.3977871 -0.820697 -0.7564913 -0.3285319 -0.565498 -0.4273744 -0.2443651 -0.8704234 -0.344259 -0.2324857 -0.9096353 -0.400637 -0.3500946 -0.8467136 -0.3775014 -0.1863445 -0.9070659 -0.4206142 -0.4013929 -0.8136138 -0.4284709 -0.2749409 -0.8607091 -0.3977013 -0.2698251 -0.8769425 -0.4867144 -0.3194209 -0.813068 -0.3940976 -0.3039672 -0.8673471 -0.3966978 -0.4506388 -0.7997222 -0.7302646 -0.3963003 -0.5564708 -0.7287078 -0.4018325 -0.554541 -0.7226005 -0.3179762 -0.6137914 -0.7244191 -0.3174462 -0.6119191 -0.6159617 -0.6850082 -0.3890438 -0.6257168 -0.6713206 -0.3972496 -0.6823185 -0.3958339 -0.6146194 -0.6998857 -0.3802934 -0.6045966 -0.5751392 -0.7254677 -0.3780364 -0.5636139 -0.7398137 -0.367444 -0.3484191 -0.9164354 -0.196851 -0.2079414 -0.9707177 -0.120281 -0.1710729 -0.9754478 -0.1386928 -0.2850448 -0.946662 -0.1502681 -0.635155 -0.5754158 -0.5152426 -0.6933896 -0.4745745 -0.5422085 -0.6915826 -0.4853011 -0.5349732 -0.5195526 -0.7767597 -0.3559629 -0.5049463 -0.7913793 -0.3445983 -0.6677946 -0.4688409 -0.5781338 -0.666459 -0.4657917 -0.582126 -0.6394641 -0.57147 -0.5143032 -0.4446831 -0.8356276 -0.3224647 -0.4608541 -0.8225458 -0.3332148 -0.6152371 -0.551041 -0.5637705 -0.6394841 -0.4729501 -0.6061174 -0.5872092 -0.6430138 -0.4916489 -0.5931286 -0.6329521 -0.4975642 -0.5397695 -0.6952344 -0.4746558 -0.6081828 -0.5534384 -0.5690516 -0.5905263 -0.5411881 -0.5986604 -0.6017535 -0.5389868 -0.5893947 -0.5487121 -0.6889418 -0.473576 -0.3379074 -0.9017367 -0.2696101 -0.2293143 -0.94658 -0.2267187 -0.1962354 -0.9513163 -0.2376739 -0.3577116 -0.8843262 -0.3000159 -0.4895191 -0.7483583 -0.4475834 -0.5021937 -0.7338559 -0.4574464 -0.5662673 -0.6109399 -0.5532574 -0.5648914 -0.615352 -0.5497633 -0.469412 -0.7640525 -0.4425792 -0.4414468 -0.7880686 -0.4290369 -0.4357098 -0.7936354 -0.4246174 -0.5235134 -0.6668327 -0.530347 -0.5247153 -0.6631069 -0.5338194 3.17015e-6 0 -1 3.68013e-7 0 -1 1.58507e-6 0 -1 -1.58507e-6 0 -1 5.5202e-7 0 -1 0.8776283 0.1450582 0.4568663 0.950655 0.03645515 0.3081008 0.8776306 0.1450642 0.4568598 0.8853518 0.06117868 0.460879 0.9486778 0.1450583 0.2810134 0.9911858 0.03314352 0.1282669 0.9568119 0.06467574 0.2834221 0.9486783 0.1450563 0.2810127 0.6425843 0.1450235 0.7523655 0.9848681 0.1450613 0.09482717 0.9979758 0.03019386 -0.05597043 0.9848684 0.1450572 0.09483057 0.9931051 0.06781148 0.09562367 0.9848689 0.1450554 -0.09482723 0.9707893 0.02760654 -0.2383404 0.9848674 0.1450635 -0.09483063 0.9929135 0.07058691 -0.09560531 0.9486779 0.1450582 -0.2810134 0.6459197 0.04855668 0.7618597 0.9562611 0.07300227 -0.2832586 0.9105518 0.02536684 -0.4126161 0.9486784 0.1450561 -0.2810125 0.8776307 0.1450595 -0.4568614 0.8776276 0.145064 -0.4568657 0.8193166 0.02349007 -0.5728601 0.8845109 0.07505267 -0.460443 0.7743305 0.1450641 -0.6159293 0.7001817 0.02197325 -0.7136265 0.77433 0.1450676 -0.615929 0.7803005 0.07674682 -0.6206779 0.6425806 0.1450584 -0.7523617 0.6425759 0.1450631 -0.7523649 0.5572103 0.02082264 -0.8301103 0.6474632 0.07808518 -0.7580859 0.4872156 0.1450585 -0.8611497 0.3952732 0.02002626 -0.9183454 0.4908825 0.07905769 -0.8676314 0.4872151 0.1450587 -0.8611501 0.3139492 0.145059 -0.938293 0.2198706 0.01958805 -0.9753324 0.3162968 0.07967239 -0.9453089 0.3139506 0.1450582 -0.9382928 0.1290443 0.1500868 -0.9802151 0.08603692 0.04867714 -0.9951021 0.1331744 0.145112 -0.9804117 0.1341981 0.07721668 -0.9879416 -0.06011301 0.1744914 -0.9828221 0 0.04867726 -0.9988146 -0.08602565 0.04867702 -0.9951032 0 0.1434949 -0.9896512 0 0.04867744 -0.9988146 -0.165064 0.04441112 -0.9852825 -0.0988686 0.1454895 -0.9844074 -0.09977281 0.05682134 -0.9933866 -0.3070986 0.04873228 -0.9504293 -0.3041881 0.1455838 -0.9414218 -0.2124792 0.1454618 -0.9662782 -0.2143767 0.06004416 -0.9749037 -0.2465666 0.1738458 -0.9534057 -0.2366696 0.04869264 -0.9703693 -0.3070213 0.04869228 -0.9504563 0.7750194 0.04413515 0.6303945 0.6425634 0.1450522 0.7523777 0.6485159 0.05309689 0.759347 0.77433 0.1450671 0.615929 0.8777703 0.04011327 0.4773996 0.7743302 0.1450679 0.6159287 0.781323 0.05731165 0.6214902 0.4566102 0.8877388 0.05854177 0.3476095 0.9166537 -0.1972653 0.3564909 0.9290682 0.09872418 0.2298692 0.9071717 -0.35242 0.2112879 0.9059569 -0.3668781 0.1268558 0.963142 -0.2372031 0.3302363 0.9433715 0.03153038 0.3225229 0.9462252 0.02524125 0.1850442 0.938919 -0.2901551 0.1865323 0.939439 -0.2875066 0.2700368 0.9125881 -0.3070232 0.1302735 0.9599921 -0.2478792 0.2723236 0.9129614 -0.3038774 0.2729539 0.9430565 -0.1901075 0.2741814 0.905642 -0.3234767 0.1691002 0.9270364 -0.3346772 0.2066284 0.900036 -0.3837184 0.2399937 0.9427539 -0.2315561 0.2387732 0.9420715 -0.2355605 0.5221136 0.8336286 0.1801691 0.268774 0.9623466 -0.04061442 0.2819941 0.9590433 -0.02674669 0.2947199 0.911134 -0.2880541 0.2265789 0.9694129 -0.0943436 0.2941697 0.910605 -0.2902809 0.2196944 0.9699561 -0.1044971 0.1639039 0.9716467 -0.1704061 0.1587402 0.9708257 -0.1797196 0.4542225 0.8908854 0.002330362 0.3541049 0.9156694 -0.1901562 0.1410148 0.956128 -0.2567768 0.3031959 0.9128471 -0.2734637 0.164942 0.9197546 -0.3561539 0.3599854 0.9129685 -0.1920917 0.1442643 0.8931078 -0.4260825 0.1215675 0.8886852 -0.4421087 0.1323704 0.8917462 -0.4327434 0.3677765 0.9097809 -0.1924558 0.311962 0.9413316 -0.1287426 0.3137481 0.9412222 -0.1251524 0.1644565 0.8956469 -0.4132443 0.2275948 0.9353513 -0.2707741 0.3140934 0.911053 -0.2670724 0.4512265 0.8923528 0.01005125 0.4505674 0.892485 -0.02144062 0.1618394 0.9533618 -0.2547732 0.3633075 0.9113811 -0.1933705 0.404285 0.9141882 0.02852445 0.423902 0.903505 0.06313335 0.3449904 0.9104591 -0.2281364 0.150977 0.8949396 -0.4198681 0.1450116 0.8983256 -0.4147084 0.3925139 0.9105457 -0.1297667 0.4000404 0.9105001 -0.1046767 0.3385315 0.9094793 -0.2413375 0.3395061 0.9081762 -0.2448504 0.1448305 0.9127836 -0.3819035 0.1473416 0.9135981 -0.3789845 0.3360765 0.8970393 -0.2870071 0.3199298 0.9092187 -0.2663952 0.3634743 0.9308007 0.03868597 0.3237187 0.910639 -0.2567933 0.3772543 0.9242718 0.05831766 0.5232958 0.8342607 0.1736973 0.512422 0.8523943 0.1041523 0.1651548 0.9629803 -0.2130559 0.1674227 0.9637029 -0.2079573 0.6202698 0.7030745 0.347781 0.6314531 0.73755 0.2393471 0.2741321 0.959152 -0.06985002 0.2660667 0.9605228 -0.08126854 0.3256163 0.9454851 -0.005654692 0.1899501 0.9243186 -0.33099 0.2054773 0.9244717 -0.3211404 0.359921 0.9088483 -0.2108356 0.3124337 0.9497503 -0.01896405 0.459643 0.8421808 -0.2818862 0.2215312 0.963802 -0.1483568 0.3599954 0.9082986 -0.2130661 0.227245 0.9636868 -0.1402406 0.4913064 0.8619075 0.1254332 0.2069144 0.9578635 -0.1992083 0.6129392 0.7537091 0.2371247 0.5987347 0.724606 0.3412668 0.1206551 0.8968892 -0.4254789 0.3977358 0.9064069 -0.1422417 0.3959904 0.9044722 -0.1584987 0.4948328 0.8613299 0.1151142 0.5005033 0.8631653 0.06665056 0.6174766 0.5450075 0.5671769 0.6278801 0.5487642 0.5519279 0.6768362 0.6499461 0.3456341 0.4422787 0.8947867 -0.06120932 0.4500114 0.8928018 -0.01987177 0.3471232 0.9351164 -0.07115364 0.3617653 0.9308051 -0.05222815 0.3413935 0.9336688 -0.1082277 0.5930066 0.7699991 0.2354672 0.572475 0.7414828 0.3499652 0.2445397 0.936784 -0.2502723 0.4837546 0.8700224 0.09509378 0.1762836 0.9517756 -0.2510927 0.1768051 0.9521163 -0.2494285 0.6517763 0.5927913 0.4730605 0.6425026 0.6668123 0.3775606 0.6312873 0.6305766 0.451497 0.4905194 0.8594996 0.1437048 0.5727568 0.8022768 0.168231 0.08676463 0.9387347 -0.3335402 0.4418246 0.8950687 -0.06035917 0.2306441 0.9291491 -0.2889381 0.2316542 0.9324673 -0.2772023 0.5716753 0.7894924 0.2233594 0.5472668 0.7600446 0.3504733 0.1263871 0.9004 -0.4163007 0.2223688 0.9280619 -0.2987527 0.4443111 0.8919349 -0.08390349 0.5455713 0.5920297 0.5931718 0.5935221 0.6815352 0.428067 0.5924056 0.6474973 0.4793776 0.610513 0.6866387 0.3947166 -0.355877 0.868385 -0.3453392 0.6209206 0.5817071 0.525428 0.4848045 0.8742501 0.02552366 0.06715184 0.9096756 -0.4098548 0.4864889 0.8696339 0.08405685 0.08803158 0.906143 -0.4137092 0.09141343 0.9082815 -0.4082502 0.05286049 0.9265704 -0.3723886 0.5560597 0.8047888 0.2076358 0.2814819 0.9379528 -0.2025154 0.5229291 0.7841681 0.3341041 0.2796347 0.937224 -0.2083646 0.01528334 0.9183431 -0.3954902 -0.007926523 0.9473907 -0.3199813 0.1826364 0.9206148 -0.3451264 0.4720937 0.8804945 0.0430932 0.1265108 0.9364948 -0.3270668 0.4899003 0.8681885 0.07903504 0.1679512 0.9147158 -0.3675425 0.1669496 0.9143031 -0.3690227 0.3187589 0.9350264 -0.1553009 0.3165571 0.9352173 -0.1586197 0.5061073 0.8038463 0.3125484 0.5478479 0.8140051 0.1930244 0.4694676 0.6200878 0.6285628 0.5382267 0.7030827 0.4647439 0.5739377 0.6046362 0.5522777 0.4788248 0.8777731 0.0155363 0.5086073 0.8608091 -0.01806432 0.2067923 0.9280644 -0.3097314 0.3868231 0.8323309 0.3969804 0.5175575 0.6964299 0.4971113 0.5507221 0.7352446 0.395121 0.5264158 0.6674991 0.5266226 0.5381473 0.8238371 0.1780173 0.2538833 0.9348711 -0.2481119 -0.01397097 0.9982026 -0.05827766 0.4962904 0.8156828 0.2972501 -0.08135563 0.9932183 -0.08305889 0.0129888 0.9998638 0.01018935 0.3166722 0.9474066 -0.04625499 0.3084902 0.9494937 -0.05740791 0.5346571 0.7503024 0.3888289 0.4950789 0.7240644 0.4802371 0.5065513 0.6620602 0.5523425 0.2125035 0.951992 -0.2203488 0.4856631 0.828913 0.2775509 0.01563918 0.997694 -0.06604766 0.1005768 0.898027 -0.4282897 0.5270586 0.8359078 0.1531909 -0.04949164 0.9410488 -0.334631 -0.08796101 0.9532464 -0.2891095 -0.09557896 0.951082 -0.2937817 0.2292231 0.957275 -0.1762996 0.4778845 0.8461251 0.2360059 0.4981574 0.8447628 0.1954863 0.01427572 0.9978064 -0.06464201 0.3935244 0.6884962 0.6091892 0.008370637 0.9932418 -0.1157621 0.5215671 0.7674775 0.3727547 0.5152745 0.7669526 0.3824601 0.4916568 0.6622036 0.5654734 0.4796766 0.7403569 0.4709374 0.04157197 0.9984765 -0.03628408 0.4650567 0.8573796 0.2205058 0.4682028 0.7379404 0.4860352 0.4588795 0.786396 0.4135348 0.466613 0.8569786 0.2187693 0.0748378 0.9963801 -0.0403257 0.5050845 0.7918832 0.3432358 0.07392394 0.9965142 -0.03866308 0.2060398 0.9248367 -0.3197262 0.1003893 0.9913627 0.0843929 0.4487151 0.7977884 0.4027266 0.4581989 0.7365882 0.4974853 0.2655836 0.956094 -0.1238939 0.2732776 0.9552087 -0.1135603 0.2682436 0.9327735 -0.2407884 0.116905 0.9925207 -0.03515446 0.4641696 0.8573024 0.2226638 0.0634678 0.9959917 -0.06302762 0.1089368 0.919727 -0.3771407 0.49246 0.8060603 0.3282532 0.4868213 0.8166269 0.3100414 0.4430238 0.8098949 0.3844481 0.4500172 0.7374888 0.503582 0.4470199 0.7384551 0.5048341 0.4402055 0.8218273 0.3616891 0.01894384 0.9915057 -0.1286768 0.02955329 0.978272 -0.2052083 0.06605595 0.9953094 -0.07068341 0.131436 0.9912133 -0.0148645 0.244281 0.953516 -0.1764486 0.4814708 0.8275297 0.2887569 0.3515812 0.7877144 0.5058626 0.049456 0.902161 -0.4285556 0.4251425 0.8419699 0.3321756 0.4276387 0.8312949 0.3550691 0.3698096 0.9289602 0.01655244 0.3548575 0.934918 0.0021739 0.09112966 0.9929142 -0.0762692 0.1957995 0.9155921 -0.3512174 0.1911194 0.9371069 -0.2920687 0.197737 0.9159032 -0.3493156 0.1278445 0.9907338 -0.0458523 0.1676759 0.9857093 -0.01618504 0.1864927 0.9824317 0.006962716 -0.01875394 0.9727635 -0.2310402 0.126136 0.8988 -0.4198196 0.109297 0.9914491 -0.07129561 0.3125751 0.9327223 -0.1797941 0.2856698 0.9321746 -0.2223588 0.2820903 0.9320685 -0.2273176 0.03364568 0.9895914 -0.139917 0.2178378 0.9197762 -0.3264331 0.2233802 0.91985 -0.3224553 0.2115775 0.977361 -6.01892e-4 0.02122986 0.9782002 -0.2065762 0.4723234 0.8774504 0.08361589 0.4932654 0.8608598 0.1249384 0.1626322 0.9859739 -0.0374999 0.2356423 0.9193366 -0.3151082 0.3541082 0.9277275 -0.1180214 0.3466064 0.9281135 -0.1359024 0.1827805 0.9456402 -0.2689908 0.1832268 0.9466878 -0.2649722 0.1853322 0.9091503 -0.3729581 0.1671444 0.9381346 -0.3032594 -0.001607954 0.9589155 -0.2836875 -0.03887009 0.9509092 -0.3070194 0.2928556 0.9304389 -0.2202702 0.1366707 0.9017956 -0.4099827 0.4226911 0.903669 0.0686624 0.5087203 0.8533955 0.1136653 0.434068 0.8956409 0.0970174 0.1408795 0.9856924 -0.09253984 0.2730806 0.949782 -0.1527779 0.04331952 0.964747 -0.2595896 0.02823615 0.9772945 -0.2099958 0.05647313 0.9640148 -0.2597815 0.08490371 0.9108662 -0.403874 0.1693161 0.9845737 -0.04412341 0.3925156 0.9190405 -0.03600317 0.409604 0.9122548 0.003991782 0.09356981 0.9838361 -0.15268 0.2421171 0.9702362 0.004598379 0.2403705 0.9187207 -0.3133281 0.2362531 0.9461503 -0.2213239 0.03573298 0.9627096 -0.268167 0.01030933 0.9594676 -0.2816306 0.218245 0.9154587 -0.3380894 0.3157913 0.9261179 -0.206353 0.1110938 0.9106779 -0.3978996 0.3238651 0.9269065 -0.1896201 0.2679896 0.9574221 0.1073533 0.1271985 0.898166 -0.4208545 0.1314305 0.9215418 -0.3653584 0.1320466 0.9217379 -0.3646409 0.3195611 0.9233042 -0.2130494 0.2141777 0.9763547 -0.02931469 0.2478014 0.9688107 -6.14844e-4 0.1631176 0.9027288 -0.3980875 0.08418953 0.9641741 -0.2515563 0.166841 0.904347 -0.3928366 0.1538746 0.9265246 -0.3433289 0.5536726 0.8080786 0.2011358 0.08817172 0.9034976 -0.4194257 0.4777843 0.8772811 0.04582649 0.1527419 0.9838446 -0.09338009 0.1670514 0.9829797 -0.07645237 0.396761 0.9169213 -0.04285234 0.2258996 0.9736683 -0.03065323 0.09286952 0.9739603 -0.2068251 0.1011395 0.9663998 -0.23631 0.1032244 0.9748569 -0.1974818 0.3066398 0.9467113 -0.09853893 0.3144791 0.9451866 -0.08789247 0.1637262 0.8917462 -0.4218797 0.2306386 0.9121519 -0.3387992 0.187075 0.9073237 -0.3765191 0.2925639 0.9560493 0.01939862 0.2776364 0.960672 0.005228221 0.25299 0.9475492 -0.195312 0.3447062 0.938055 -0.03507685 0.2811104 0.9472866 -0.1537053 0.1541096 0.9794466 -0.1301331 0.1576236 0.9798314 -0.1228216 0.2520915 0.9142811 -0.3170805 0.1071303 0.9653657 -0.2378914 0.2214847 0.9730866 -0.06361627 0.1123172 0.9098715 -0.3993981 0.2323317 0.9714008 -0.04901516 0.1163644 0.9112929 -0.3949742 0.5421462 0.8266859 0.1505587 0.553483 0.8077898 0.2028111 0.393133 0.9152774 -0.08782845 0.3977345 0.9148696 -0.06943291 0.2335264 0.9092459 -0.3445828 0.3395206 0.9180533 -0.2047048 0.2848125 0.9441437 -0.1657549 0.1483888 0.923138 -0.3546791 0.1790913 0.8991931 -0.3992221 0.358618 0.9199492 -0.1583873 0.3524281 0.9204691 -0.1689115 -0.06977021 -1.24556e-5 -0.9975631 -0.06975561 -1.05388e-5 -0.9975642 -0.0698111 1.38904e-5 -0.9975603 -0.06975656 8.94762e-7 -0.997564 -0.06975752 7.65884e-7 -0.997564 -0.06975561 -9.42221e-7 -0.9975641 -0.06975626 1.03883e-6 -0.9975641 -0.06975442 -2.00398e-6 -0.9975642 -0.06976449 2.84486e-6 -0.9975635 -0.06975114 3.59295e-7 -0.9975645 -0.0697565 6.17828e-7 -0.9975641 -0.06975567 -1.67301e-6 -0.9975641 -0.0697565 0 -0.9975641 -0.06975632 1.30555e-7 -0.9975641 -0.994778 0.06975537 0.07450491 -0.994963 0.06828981 0.07338333 -0.9941185 0.06851452 0.08387082 -0.772502 0.6035349 0.1974502 -0.633987 0.7689247 0.08255529 0.2813544 0.9234431 0.2609455 0.2813481 0.9234443 0.2609483 -0.6339809 0.7689296 0.08255678 0.4863581 0.8571242 0.1696873 -0.6286922 0.7613795 0.1582637 -0.6286926 0.761379 0.1582642 -0.978621 0.1767463 0.1051749 0.4863446 0.8571305 0.1696944 -0.9745671 0.1919121 0.1157103 0.8062298 0.5907196 0.03230953 -0.9082376 0.3863677 0.1607001 -0.902065 0.4014497 0.1584836 0.7975295 0.6026506 -0.02755087 -0.7893035 0.5966913 0.1447744 0.8062396 0.5907067 0.03230214 -0.7934419 0.6026195 0.08543896 -0.7934376 0.6026248 0.08544069 0.8021216 0.5965756 -0.02643293 -0.789289 0.5967105 0.1447739 -0.9788057 0.1884468 0.08017057 -0.9110051 0.4042201 0.0817064 -0.06882691 0.9267306 0.3693689 -0.9043506 0.4082197 0.1245263 0.02750992 0.9376365 0.3465272 -0.9738155 0.2047339 0.09883129 -0.9043416 0.4082408 0.1245222 -0.9071891 0.4122665 0.08393067 -0.9796988 0.184207 0.07910835 -0.3050821 0.8824505 0.3580588 -0.1900336 0.9167242 0.3514315 0.9840323 0.1752905 -0.03088265 0.02348387 0.9569889 0.2891725 0.02349865 0.9569913 0.2891637 0.8928363 0.4395335 0.09825319 0.9405696 0.339597 -0.001708745 0.9366019 0.3465127 0.05201882 0.6393002 0.76893 -0.006482243 0.650335 0.7565885 0.06810653 0.6503373 0.7565863 0.06810641 0.6452484 0.7639546 -0.005283892 0.2772912 0.9389326 0.2037528 0.7685421 0.6168195 0.169932 0.8073174 0.573914 0.1373367 0.2772955 0.9389324 0.2037479 0.4810522 0.8712909 0.09716516 0.481042 0.8712963 0.09716707 0.4468975 0.894552 0.007717847 0.4749932 0.8799265 0.01052623 -0.193787 0.9348097 0.2976196 -0.1938213 0.9347994 0.2976295 -0.501107 0.7960107 0.3394978 -0.4099649 0.8502885 0.3300579 0.01933944 0.9730234 0.2298946 0.01935333 0.973024 0.229891 0.589812 0.7651486 0.2582044 -0.4126188 0.8631251 0.2911372 0.6698346 0.7146821 0.2013731 -0.4126376 0.8631127 0.2911475 -0.7090478 0.642891 0.2897284 -0.6244347 0.725893 0.2883761 0.9039109 0.425394 0.0445559 0.2715844 0.9543561 0.1242836 0.2313764 0.9723573 0.03140342 0.2715865 0.9543555 0.1242831 0.2655441 0.9634018 0.03665012 0.3699069 0.8750538 0.3121697 -0.1978384 0.9504704 0.239721 -0.1977887 0.9504843 0.2397069 0.4935299 0.8259961 0.2723212 0.6400154 0.7464754 0.1820849 -0.6068435 0.7476864 0.2696405 0.003455221 0.9987725 0.04941302 0.006756544 0.9987287 0.04995512 0.9816533 0.1835527 -0.05162632 0.01359158 0.9889661 0.1475175 0.9774774 0.2082842 -0.03399586 0.0135793 0.9889656 0.1475223 0.8142064 0.5743952 0.08448868 -0.4162938 0.8776147 0.2376802 0.8101702 0.5795987 0.08769118 -0.4162659 0.8776308 0.2376701 -0.2249449 0.9724641 0.06093907 0.4900769 0.842963 0.221897 -0.2100286 0.975651 0.06319147 0.4900954 0.8429548 0.2218869 -0.203336 0.9660704 0.1592562 -0.2033119 0.9660765 0.1592501 -0.8814091 0.4234578 0.2092881 -0.7964974 0.5614172 0.2245056 0.1936125 0.9191046 0.3431633 0.2850247 0.9056773 0.3138626 -0.642795 0.7314492 0.2275888 0.9132687 0.4045478 -0.04776531 -0.6244987 0.7489126 0.2216559 0.9187498 0.3922968 -0.04474341 0.9239436 0.3824613 -0.007187187 0.9165958 0.3998151 -2.32824e-4 -0.4409908 0.8943477 0.07529562 -0.4212388 0.8921119 0.1633836 0.6552327 0.74307 0.1360783 -0.427275 0.900728 0.07826387 -0.4212561 0.892103 0.1633884 0.6685832 0.732649 0.1273663 -0.7855776 0.5857746 0.1993393 1.30598e-5 0.08717072 -0.9961935 0 0.08715546 -0.9961947 0 0.08715683 -0.9961947 0 0.08715671 -0.9961946 -0.9961947 0.08715611 0 -0.9961897 0.08721417 3.37283e-5 -1.43231e-6 0.08715718 0.9961947 -7.62747e-4 0.08953678 0.9959833 0 0.08716088 0.9961943 -0.1153771 -0.2259128 -0.9672908 -0.2056745 0.1615809 -0.965189 -0.2314196 0.1930009 -0.9535176 0.08516228 0.267208 -0.9598684 -0.07474184 -0.2711139 -0.9596411 0.09201878 0.2914971 -0.9521356 -0.08996254 -0.2977322 -0.9504011 0.08469957 0.2683084 -0.9596024 0.09281355 0.2920042 -0.951903 -0.08092874 -0.2914447 -0.9531582 -0.07508361 -0.2703905 -0.9598184 0.1236698 0.2274664 -0.9659011 0.1235368 0.2287271 -0.9656203 -0.1145557 -0.2295624 -0.9665289 0.1314201 0.2808996 -0.9506968 0.1114612 0.257395 -0.9598563 0.111122 0.2580973 -0.9597072 0.1201202 0.2773904 -0.9532187 0.1441665 0.2152143 -0.9658669 0.1441671 0.2152768 -0.9658529 -0.1037458 -0.2611218 -0.9597147 -0.134321 -0.2826694 -0.9497662 -0.1109242 -0.2791941 -0.9538064 -0.1042255 -0.2601235 -0.9599338 0.1633944 0.2015748 -0.9657484 0.1656213 0.2619894 -0.950753 0.1350356 0.2451665 -0.9600307 0.1437949 0.2637054 -0.9538253 0.1345089 0.2466804 -0.9597167 0.1553916 0.2327569 -0.9600405 0.1806745 0.1712574 -0.9685183 0.1702234 0.2043433 -0.9639854 0.1947461 0.2360177 -0.9520345 0.1684013 0.2511811 -0.9531785 0.1561057 0.2328403 -0.9599044 0.1797052 0.215053 -0.9599261 0.1792435 0.2150008 -0.9600243 0.1946775 0.2335125 -0.9526661 -0.1427528 -0.2092023 -0.9673966 0.2011499 0.1833212 -0.9622537 0.2044174 0.1914002 -0.9599894 0.2232522 0.203628 -0.9532545 0.2524008 0.1663356 -0.953219 0.2262973 0.2038078 -0.9524977 -0.1710691 -0.1908086 -0.9666061 -0.1460044 -0.2110089 -0.9665185 0.2224531 0.1486039 -0.9635516 -0.1702435 -0.2556555 -0.9516603 -0.1281421 -0.2475345 -0.9603679 -0.1382641 -0.2712866 -0.952516 -0.1272774 -0.2497323 -0.9599137 0.2781465 0.1261913 -0.9522134 0.2528145 0.1676475 -0.9528795 0.2354414 0.1497994 -0.9602748 0.2971296 0.08195877 -0.9513132 0.274604 0.1210992 -0.9539014 0.2557939 0.1128051 -0.9601274 0.2563588 0.1137578 -0.9598642 0.3081308 0.03477072 -0.9507085 0.2721505 0.06868696 -0.9598002 0.2731823 0.06981009 -0.9594259 0.2808731 0.0240221 -0.9594443 0.2890434 0.07294976 -0.9545325 0.3109048 -0.01381355 -0.9503407 0.2831308 -0.01329147 -0.9589893 0.2830778 0.02324086 -0.9588153 0.2960024 0.02430206 -0.954878 0.2762418 -0.03710103 -0.9603718 0.287191 -0.01765394 -0.9577107 -0.1808325 -0.1688981 -0.968903 0.3035016 -0.01865565 -0.9526483 0.3024364 -0.06167757 -0.9511721 0.2824131 -0.05478608 -0.9577273 0.273574 -0.06095886 -0.9599173 0.29864 -0.05793404 -0.9526058 0.2661598 -0.08487647 -0.9601849 0.294467 -0.1101486 -0.9492927 0.2876516 -0.09047329 -0.9534523 0.2673891 -0.0841006 -0.9599116 -0.175889 -0.1909328 -0.9657163 -0.2086166 -0.2291421 -0.950775 -0.1578105 -0.2320795 -0.9598098 -0.1578844 -0.2305755 -0.9601601 -0.1700794 -0.2483851 -0.9536131 0.2740984 -0.1191623 -0.9542905 0.2551012 -0.1119748 -0.9604088 0.271096 -0.1522729 -0.9504315 0.2564587 -0.111495 -0.960103 -0.1815757 0.1717845 -0.9682564 -0.1924281 -0.2038398 -0.9599066 -0.171366 -0.1234219 -0.9774461 0.2606806 -0.1537588 -0.9531023 0.2416009 -0.1882525 -0.9519402 0.2401005 -0.1416204 -0.9603622 0.2390465 -0.141898 -0.9605841 -0.2050361 0.1662954 -0.9645237 -0.2165985 -0.135823 -0.9667664 -0.2022491 -0.1566692 -0.9667214 -0.2357047 0.1928557 -0.9524968 -0.2113035 0.182106 -0.9603064 -0.1274184 0.1584067 -0.9791179 -0.2075164 -0.222437 -0.9526064 -0.1900366 -0.2037015 -0.9604123 0.2126915 -0.2244569 -0.9509898 0.232999 -0.1874276 -0.9542444 0.2169634 -0.1745274 -0.9604515 0.2150968 -0.1745247 -0.9608718 0.1713649 -0.1957711 -0.9655609 -0.2034541 -0.1622455 -0.9655479 0.1457917 -0.2148501 -0.965704 -0.1472731 0.2134621 -0.965787 -0.1706637 0.1955726 -0.9657253 -0.1926082 -0.09345656 -0.9768152 -0.1709217 0.1956066 -0.9656728 0.12334 -0.2222918 -0.9671472 0.1456468 -0.2183962 -0.9649301 0.1781588 -0.2558701 -0.9501527 -0.2373468 -0.1904904 -0.9525649 -0.1862351 0.2075569 -0.9603315 0.1965272 -0.221168 -0.9552287 0.1840139 -0.2070862 -0.9608612 -0.2373446 -0.1904903 -0.9525655 0.1897643 -0.2077357 -0.9596018 -0.2175675 -0.1756938 -0.9601022 -0.2173397 -0.1744332 -0.9603836 -0.2268051 -0.1270795 -0.9656139 -0.2403264 -0.09917056 -0.965613 -0.2017311 0.2278784 -0.9525629 -0.2275718 -0.1310529 -0.9649022 -0.186762 0.2109679 -0.9594857 -0.2017309 0.2278777 -0.9525631 -0.1315333 0.2168942 -0.9672931 0.1555869 -0.2334661 -0.9598366 0.1544829 -0.233225 -0.9600735 0.1345393 -0.2731528 -0.952516 0.1686683 -0.2530977 -0.9526242 -0.2409411 -0.1415942 -0.9601556 0.1042139 -0.2366647 -0.9659862 -0.2631903 -0.1528058 -0.9525656 -0.2631922 -0.1528055 -0.9525651 -0.2436652 -0.1414694 -0.9594861 -0.2350409 -0.06532567 -0.9697878 0.1191097 -0.2420965 -0.9629133 -0.1438472 0.2207821 -0.9646571 -0.2441166 -0.09717339 -0.964865 -0.2029407 -0.01838213 -0.9790185 -0.2603968 -0.1010348 -0.9602008 -0.2831032 -0.111676 -0.9525656 -0.2831022 -0.1116765 -0.9525659 -0.2620881 -0.1033869 -0.95949 0.08213359 -0.2450549 -0.9660239 0.08541363 -0.2472842 -0.965171 -0.1086497 0.2256307 -0.9681354 0.1240706 -0.2515909 -0.9598482 0.1250247 -0.2520806 -0.9595959 0.1347734 -0.273292 -0.952443 -0.2566248 -0.01822453 -0.9663394 -0.2525589 -0.0479542 -0.9663925 -0.1118461 0.2272323 -0.9673966 -0.2597324 -0.01645278 -0.9655405 -0.2538275 -0.0573877 -0.9655456 0.03587698 -0.2528082 -0.966851 0.05866938 -0.2482017 -0.9669301 -0.2726017 -0.06251859 -0.9600937 -0.2966341 -0.06802976 -0.9525651 -0.2733964 -0.06351 -0.9598026 -0.2966337 -0.06802952 -0.9525651 -0.3034734 -0.02284765 -0.952566 -0.2983758 -0.01920157 -0.9542554 -0.2796351 -0.02474808 -0.9597874 0.06118547 -0.2504544 -0.9661931 -0.1651642 0.2556816 -0.9525481 -0.1501488 0.2353589 -0.9602404 -0.1528655 0.2365903 -0.9595089 -0.1651628 0.2556251 -0.9525635 0.06381809 -0.2727236 -0.9599736 0.09706532 -0.2982942 -0.9495256 0.09126943 -0.2659612 -0.9596534 0.08991545 -0.2652558 -0.9599764 0.09980756 -0.2908461 -0.9515498 -0.0888921 0.2370222 -0.967429 0.01236033 -0.253485 -0.9672604 0.03437215 -0.2555397 -0.9661874 0.04930132 -0.3086661 -0.949892 0.06444019 -0.2719647 -0.9601472 0.06934887 -0.2926859 -0.9536906 -0.08786588 0.241113 -0.9665114 -0.06785881 0.2483264 -0.9662967 -0.009429097 -0.255801 -0.9666835 -0.1284806 0.2857925 -0.9496396 -0.1221047 0.250931 -0.9602729 -0.1329337 0.2731839 -0.9527325 -0.1200696 0.2505612 -0.9606261 -0.1013032 0.2586345 -0.9606487 0.03719902 -0.2766364 -0.9602545 0.04086685 -0.3013188 -0.9526474 0.03755098 -0.276874 -0.9601723 0.001422643 -0.2658039 -0.9640261 -0.04162043 0.2457228 -0.9684462 -0.06677675 0.2502584 -0.9658735 -0.08323335 0.2990928 -0.950587 -0.09925788 0.2624537 -0.9598261 -0.1063299 0.2811524 -0.9537543 -0.01326358 0.2445939 -0.969535 -0.03803724 -0.2544375 -0.9663409 -0.03609436 -0.2583251 -0.9653835 -0.07099479 0.2715513 -0.9598019 -0.0769037 0.2941613 -0.9526568 -0.06863737 0.2699499 -0.9604249 0.002163469 -0.3045545 -0.9524925 -0.0316267 0.2626898 -0.964362 0.002035379 -0.27978 -0.960062 0.002813994 -0.2807506 -0.9597766 0.002214074 -0.3044702 -0.9525194 0.003656446 0.2601912 -0.9655502 0.009371697 0.2567556 -0.966431 -0.03636229 0.3025368 -0.9524439 -0.03352975 0.2772497 -0.9602127 -0.032229 0.2760192 -0.9606117 -0.03654235 0.302141 -0.9525626 -0.002872347 0.2772659 -0.960789 -0.0688458 -0.2478206 -0.9663566 -0.06973618 -0.2484925 -0.9661203 0.0340408 0.2547785 -0.9664001 0.02667516 0.2618913 -0.9647287 0.002530992 0.3048271 -0.9524044 0.001138448 0.2812302 -0.9596398 0.001227021 0.3034828 -0.9528361 -0.04204249 -0.3014386 -0.9525582 -0.04438245 -0.3041408 -0.9515928 -0.03890323 -0.2779866 -0.9597969 -0.03879827 -0.2781767 -0.9597461 0.05225872 0.2580917 -0.9647061 0.05671131 0.2526387 -0.9658973 0.03074193 0.3005253 -0.9532783 0.03069037 0.3004933 -0.9532901 0.06376004 0.2962418 -0.9529824 0.02857381 0.27976 -0.9596447 0.0290057 0.279232 -0.9597856 0.05508261 0.2752621 -0.9597899 -0.09509646 -0.2381874 -0.9665524 0.08014672 0.2473312 -0.9656106 -0.09426802 -0.2400565 -0.966171 0.0788691 0.2510794 -0.9647481 0.06089234 0.3011474 -0.9516315 0.05574566 0.2757034 -0.9596251 0.1017357 0.2373521 -0.9660817 0.1041889 0.238733 -0.9654799 0.5818486 0.8132803 0.005255162 0.5807054 0.8141138 1.82996e-6 0.5807048 0.8141143 0 0.5807155 0.8141065 0 0.5804955 0.8142631 8.75606e-4 -0.02166157 0.01458537 -0.9996591 -0.02203828 0.01362788 -0.9996643 -0.02433466 0.01180559 -0.9996342 -0.0237419 0.01063424 -0.9996616 -0.02153092 0.01414704 -0.9996681 -0.02488499 0.009767472 -0.9996427 -0.0231406 0.007735252 -0.9997023 -0.02532172 0.006209433 -0.9996601 -0.02617782 0.00186932 -0.9996556 -0.02612763 0.001699328 -0.9996573 -0.02593386 0.004848241 -0.9996519 0.2145197 -0.08809274 -0.9727389 0.2197328 -0.04053378 -0.9747177 0.2184516 -0.0420258 -0.9749425 0.4381318 -0.1933965 -0.8778601 0.3916752 -0.1352446 -0.9101096 -0.3072165 -0.03357404 -0.9510473 0.9230421 -0.1053341 0.3699975 0.9207838 -0.1103814 0.3741301 0.8501468 -0.2090599 0.4832645 0.8483253 -0.2130162 0.4847354 0.3924814 -0.1105507 -0.913092 0.3932931 -0.1124824 -0.9125066 0.3950272 -0.04053306 -0.9177749 0.394573 -0.0410909 -0.9179455 0.5521307 -0.1324911 -0.8231633 0.5911872 -0.1960217 -0.7823511 0.8781383 -0.02777427 0.4775999 0.9256471 -0.0459122 0.3755924 0.745875 -0.251644 0.6167219 0.6245682 -0.2515332 0.7393549 0.6221109 -0.2411772 0.7448569 0.7498175 -0.2404124 0.6164217 0.8567392 -0.16267 0.4894245 0.8566635 -0.1628312 0.4895036 0.5529334 -0.1114748 -0.825735 0.5553492 -0.1063122 -0.8247939 0.699805 -0.0394746 -0.7132424 0.5568971 -0.03947454 -0.8296429 0.5557516 -0.04108941 -0.8303324 0.7235048 -0.1945244 -0.6623452 0.6955527 -0.1267424 -0.7072079 0.696321 -0.1212521 -0.7074144 0.6933473 -0.1065747 -0.712679 0.8627669 -0.1113235 0.4931941 0.8630691 -0.1104925 0.492852 0.7533049 -0.2112841 0.6228088 0.7026939 -0.04464739 -0.7100902 0.6342822 -0.2110185 0.7437455 0.7546176 -0.2082929 0.622227 0.8119691 -0.1303645 -0.5689564 0.8293657 -0.1838151 -0.5276026 0.8124459 -0.1212548 -0.5702885 0.635641 -0.1642165 0.7543166 0.7753838 -0.03176957 0.6306906 0.8671188 -0.04907053 0.4956786 0.7613042 -0.1630211 0.6275668 0.8210178 -0.4485526 -0.3531717 0.761148 -0.1632968 0.6276845 0.636408 -0.1630173 0.7539298 0.8172897 -0.1056858 -0.5664523 0.8162698 -0.04464864 -0.575943 -0.2318507 -0.2959595 -0.9266355 0.9101351 -0.03947031 -0.4124272 0.8189039 -0.03947335 -0.5725719 0.9420322 -0.1601523 -0.294833 0.9021859 -0.1377392 -0.4087646 0.9067436 -0.1599645 -0.3901635 0.766958 -0.1112763 0.6319754 0.7664961 -0.1123054 0.6323538 0.6447355 -0.1119457 0.7561643 -0.2851337 -0.1862612 -0.9402157 0.6460768 -0.04326528 0.7620452 0.6323322 -0.06302785 0.7721294 0.7705625 -0.03941518 0.6361447 -0.1565341 -0.2036001 -0.9664596 0.9139243 -0.3497853 -0.2058948 -0.266982 -0.1666367 -0.9491854 0.9053266 -0.1058337 -0.4113186 0.9060773 -0.1032951 -0.4103099 0.9102565 -0.03987497 -0.4121206 0.9609528 -0.1437274 -0.2364578 0.961725 -0.1643125 -0.2192863 -0.06137812 -0.3097792 -0.9488254 -0.1034156 -0.2394564 -0.9653838 0.9541348 -0.297388 -0.03445398 -0.2767043 -0.1002088 -0.955716 -0.274024 -0.1040937 -0.9560729 -0.04151594 -0.2438308 -0.9689289 0.9654378 -0.1041171 -0.2389339 -0.1674191 -0.1679026 -0.9714832 0.9654405 -0.1116223 -0.2355107 -0.1692099 -0.1668829 -0.9713487 0.9958832 -0.07548367 -0.05018973 0.9703611 -0.04053908 -0.2382352 0.9705913 -0.03960061 -0.2374541 0.9852613 -0.1624393 -0.05360633 0.9853982 -0.1613444 -0.05439233 -0.1596019 -0.1284949 -0.9787831 -0.2367638 -0.03973054 -0.9707546 -0.2698477 -0.05609655 -0.9612677 -8.83539e-4 -0.2044205 -0.9788829 0.9653297 -0.2180801 0.1434562 -0.1081342 -0.1408275 -0.9841111 0.9922497 -0.1104882 -0.05685943 0.9785922 -0.1639717 0.1243817 -0.08991199 -0.1644137 -0.9822852 -0.08546489 -0.1667675 -0.9822853 0.9820348 -0.1432065 0.1228811 0.02709513 -0.1650095 -0.9859198 0.9930036 -0.1048626 -0.05429458 -0.01963037 -0.1652657 -0.9860537 0.9975092 -0.04109245 -0.05733251 0.9976552 -0.03941482 -0.05595248 -0.1035724 -0.1090323 -0.9886277 -0.1144694 -0.1021284 -0.9881633 -0.1697134 -0.103752 -0.9800168 0.9421843 -0.1987757 0.2697724 0.9376975 -0.2105465 0.2763941 -0.08905994 -0.1464887 -0.9851952 -0.1004871 -0.1260806 -0.9869175 0.03026205 -0.2043991 -0.9784198 0.9788038 -0.1613445 0.1261402 -0.1644253 -0.09659165 -0.9816488 -0.1650715 -0.04325765 -0.9853326 -0.1587409 -0.04001003 -0.9865093 -0.04263746 -0.1715025 -0.9842607 -0.05162382 -0.1677605 -0.9844753 -0.009356081 -0.1679482 -0.9857515 0.04277497 -0.1691974 -0.9846535 0.07659769 -0.3081632 -0.9482449 0.1225995 -0.5812941 -0.8044045 0.05958539 -0.1653537 -0.9844328 0.9855303 -0.1101714 0.1288119 0.904871 -0.213852 0.3680704 0.09214127 -0.1684926 -0.981387 0.08478087 -0.164924 -0.9826558 0.9065181 -0.2107504 0.3657997 0.9865642 -0.1039981 0.1259984 0.08981645 -0.1407489 -0.9859629 0.1565259 -0.1714707 -0.9726755 0.1018904 -0.1257622 -0.9868142 0.9486673 -0.1613997 0.2719936 0.9483454 -0.1621273 0.2726824 0.9909194 -0.04043853 0.1282325 0.9908704 -0.03975218 0.1288242 0.1240252 -0.1171167 -0.9853434 0.2705088 -0.4093225 -0.8713669 0.9559817 -0.1101612 0.2719623 0.8418418 -0.2393154 0.4837669 0.217646 -0.1438972 -0.9653621 0.9554604 -0.1051746 0.2757425 0.3390997 -0.1625233 -0.9266054 0.2363457 -0.1622174 -0.9580325 0.9159067 -0.1611872 0.3676053 0.9147136 -0.1631662 0.3696969 0.215475 -0.1075055 -0.9705737 0.9512071 -0.01299077 0.3082798 0.961059 -0.04071873 0.273327 0.2174659 -0.1115196 -0.9696763 0.2329152 -0.9666117 -0.1068291 0.2958196 -0.9538337 -0.0518853 0.2176507 -0.9663226 -0.1372917 0.06719541 -0.9306726 -0.3596295 0.02893424 -0.9184201 -0.3945473 0.1333657 -0.9504861 -0.2806952 0.4536299 -0.8728227 0.1800014 0.4652732 -0.8449972 0.26363 0.1378631 -0.9464271 -0.2920094 0.1047995 -0.9385813 -0.3287586 0.06446814 -0.930374 -0.3608991 0.1059227 -0.9412484 -0.3206742 0.06782543 -0.9302775 -0.3605326 0.1683039 -0.9596481 -0.2252762 0.1772313 -0.9619432 -0.2079769 0.3465691 -0.9366204 0.05130636 0.3749355 -0.9177587 0.1309289 0.05791902 -0.9234653 -0.3792852 0.04345846 -0.919009 -0.3918339 0.5346741 -0.7713545 0.3451609 0.2592447 -0.9641757 -0.05619323 0.2191156 -0.957123 -0.1894839 0.175413 -0.9562919 -0.2339579 0.1370884 -0.9499726 -0.2806401 0.1747419 -0.953513 -0.2455167 0.01732665 -0.9099947 -0.4142577 0.01260215 -0.9064847 -0.4220505 0.04384613 -0.9193068 -0.3910918 0.2249105 -0.9626542 -0.1507055 0.2142997 -0.9609789 -0.1749149 0.5009102 -0.7520908 0.4283088 0.5106052 -0.8060023 0.2994038 0.3991827 -0.9038733 0.1538385 0.4227813 -0.8652096 0.2695705 0.5875158 -0.6028221 0.5398433 0.6005203 -0.7007696 0.3850941 0.5460535 -0.6088816 0.5754032 0.3195706 -0.9475512 0.004639923 0.3356224 -0.9387698 0.07790368 0.01553839 -0.911953 -0.4100002 0.01610594 -0.9101625 -0.4139385 0.01377242 -0.9116821 -0.4106656 0.3250787 -0.9456717 -0.005399107 0.2691702 -0.9602115 -0.07444131 0.2810981 -0.9596047 -0.0119397 0.2583944 -0.9591494 -0.1151733 0.5062955 -0.6492097 0.5676193 0.5319076 -0.5956963 0.6018474 0.4478101 -0.6173771 0.6467702 0.5236094 -0.7220277 0.452227 0.3693327 -0.9033721 0.217973 0.4253419 -0.8495584 0.3119854 0.3601737 -0.9265299 0.1087079 0.4079416 -0.6611357 0.6296692 0.427192 -0.7799906 0.4572983 0.3292654 -0.6840336 0.6509088 0.424914 -0.604906 0.6734515 0.3353297 -0.9399721 0.06329739 0.3330475 -0.9302161 0.1541994 0.3953142 -0.7692719 0.501944 0.3273444 -0.8856444 0.3293625 -4.40264e-4 -0.917608 -0.3974864 0.2520341 -0.7563529 0.6036633 8.47947e-4 -0.9122776 -0.4095716 0.3391084 -0.6886183 0.6409449 0.3003639 -0.8210986 0.4853646 -0.01362121 -0.9162165 -0.4004521 0.2775003 -0.9161961 0.2890995 0.3538862 -0.914991 0.1937936 0.3226963 -0.8849536 0.3357446 0.3514643 -0.8338039 0.4257274 -0.02054804 -0.9202777 -0.3907262 0.2984188 -0.7729212 0.5599456 0.2221078 -0.8223593 0.523826 0.2680373 -0.8714208 0.4108307 -0.01832818 -0.9207944 -0.3896174 0.3294221 -0.894183 0.3031799 0.2693102 -0.8716787 0.4094486 0.270653 -0.8689612 0.4143108 0.2758556 -0.8895086 0.3642503 0.2636021 -0.8954654 0.358686 0.2736216 -0.8703486 0.4094198 0.4554857 -0.7836967 0.4223179 0.450599 -0.8395952 0.303382 0.4146469 -0.7989714 0.4355603 0.4261027 -0.849686 0.310597 0.2543939 -0.9253655 0.2810382 0.2218452 -0.8955298 0.3857606 0.2646945 -0.9248542 0.2730963 0.2272803 -0.9445565 0.2369739 0.2738068 -0.9412944 0.1974709 0.2535905 -0.9500882 0.1817263 -0.06368154 -0.9962959 -0.05778652 -0.1293948 -0.9849468 -0.1146168 -0.03939473 -0.9967694 -0.06999224 -0.09292501 -0.9877079 -0.1256902 0.01334482 -0.9979123 -0.06319028 0.02192187 -0.9984682 -0.05079996 -0.04027712 -0.9932543 -0.1087369 -0.1337291 -0.9691201 -0.2071786 -0.08537667 -0.98127 -0.1726846 0.1102967 -0.9938715 0.007361233 0.07746207 -0.9957709 -0.04939675 -0.05400067 -0.9835489 -0.172382 -0.003567457 -0.9939969 -0.1093498 0.01511251 -0.9956823 -0.09158879 0.1963179 -0.9805306 0.00437802 0.08807712 -0.9939149 -0.06614899 0.0654779 -0.9943588 -0.08344513 0.1388375 -0.9898403 -0.03066593 0.1328161 -0.9894685 -0.05754929 -0.001929104 -0.9883518 -0.1521741 0.002814114 -0.9893409 -0.1455913 -0.08647078 -0.9559234 -0.2805942 -0.05049276 -0.9688913 -0.2422814 0.1209064 -0.991248 -0.0530008 -0.03809511 -0.9708979 -0.2364448 0.0713725 -0.9902445 -0.1196737 0.06023466 -0.9896889 -0.1299533 0.1147016 -0.9876716 -0.1065284 0.1272665 -0.9875725 -0.09221631 0.1881592 -0.981438 -0.03708857 0.2086839 -0.977892 -0.01336121 0.01307457 -0.9768013 -0.2137482 -8.45273e-4 -0.9739924 -0.2265795 0.2680594 -0.9633979 0.00295031 0.3646122 -0.9296638 0.05275648 0.2848771 -0.9579958 0.03300207 -0.05603677 -0.9390217 -0.3392614 -0.03885871 -0.9470587 -0.3187004 0.05961209 -0.9790761 -0.1945673 0.07298564 -0.9802715 -0.1836872 0.1768739 -0.9813475 -0.07531827 0.1910938 -0.9800263 -0.05506056 0.1089056 -0.9798505 -0.167429 0.1252176 -0.980484 -0.151564 0.02237433 -0.9583959 -0.2845642 0.01867502 -0.9569448 -0.289669 -0.04364109 -0.9194921 -0.3906785 -0.02146363 -0.9310935 -0.3641487 0.2447777 -0.9689753 -0.03421729 0.2663722 -0.9638592 0.004634618 0.3488459 -0.9345046 0.07076549 0.3351652 -0.9416544 0.0308454 0.005453944 -0.9359733 -0.3520288 -0.01503008 -0.919959 -0.3917263 0.08066213 -0.9654129 -0.2479349 0.07307046 -0.9639225 -0.2559577 0.184514 -0.9768555 -0.1082038 0.1646629 -0.9775125 -0.1317395 0.0150389 -0.9279198 -0.3724765 0.3081278 -0.9502072 0.04651457 0.1266205 -0.9687659 -0.2132136 0.1167281 -0.9671612 -0.2257738 0.04024893 -0.9443962 -0.3263373 0.0408343 -0.9447375 -0.325275 0.5044049 -0.8457248 0.1741415 0.4352642 -0.8899146 0.136372 0.4147135 -0.9048876 0.09587121 -0.01564341 -0.9088921 -0.416738 -0.008953392 -0.9149385 -0.4034939 0.02527046 -0.9282464 -0.3711067 0.02265429 -0.924768 -0.3798565 0.2485985 -0.9672964 -0.05036294 0.2247564 -0.9706705 -0.0853421 0.09138751 -0.9532704 -0.2879649 0.08625435 -0.9516194 -0.2949253 0.1781656 -0.9696955 -0.1671755 0.1656317 -0.9683227 -0.1868622 0.3870806 -0.9178408 0.08796018 0.4034192 -0.9029644 0.1480144 0.05811107 -0.9357693 -0.3477918 0.05820447 -0.9358403 -0.347585 0.0382387 -0.9238927 -0.3807365 0.2858803 -0.9579135 -0.02596706 0.3134286 -0.9492621 0.0257706 0.0999459 -0.9461922 -0.3077843 0.5780099 -0.7628452 0.2897788 0.4872877 -0.8536667 0.1838585 0.008370041 -0.912108 -0.4098648 0.1276287 -0.9567824 -0.2613012 0.1325035 -0.9581072 -0.2539164 0.09541594 -0.9429788 -0.3188837 0 -1 0 0 -1 0 2.74967e-7 -1 -6.09219e-7 0 -1 0 0 -1 0 0 -1 1.39027e-6 -5.47908e-7 -1 0 -0.07485002 0.9520381 -0.2966834 -0.07821029 0.9499613 -0.3024183 -0.01726257 0.9518367 -0.3061195 -0.01903265 0.9501627 -0.311173 0.04118913 0.951632 -0.3044667 0.04060977 0.9503663 -0.308472 0.09839016 0.9514209 -0.2917494 0.09852355 0.9505731 -0.2944555 0.1522592 0.9512071 -0.2683698 0.1525871 0.9507787 -0.2696983 0.2008296 0.9509874 -0.2351393 0.2008298 0.9509871 -0.2351405 0.2412586 0.9512032 -0.1923714 0.2425057 0.9507794 -0.1928977 0.2727742 0.9514185 -0.1428192 0.2754155 0.9505738 -0.1433732 0.2942836 0.9516294 -0.08831077 0.2983132 0.9503688 -0.08836513 0.3050507 0.9518368 -0.03083401 0.3103113 0.9501655 -0.02987796 0.3047436 0.9520369 0.02751863 0.3109236 0.9499634 0.02993702 0.2933995 0.9522356 0.08464086 0.3000852 0.9497618 0.08889019 0.2714806 0.9524308 0.1384699 0.2781524 0.9495604 0.1447975 0.2398257 0.952621 0.1870746 0.2458838 0.9493618 0.1955851 0.1996107 0.9528074 0.2287215 0.2044245 0.9491692 0.2393506 0.1626881 0.9524794 0.2575182 0.142912 0.9587422 0.2457429 0.1400098 0.9506174 0.2769911 0.1001033 0.952782 0.286681 0.1004768 0.9494372 0.2974452 0.04540997 0.9518296 0.3032467 0.04330784 0.9484199 0.314045 0.3313695 0.2424459 0.9118192 0.3261236 0.2341656 0.9158657 0.2264786 0.1997382 0.9533164 0.3221653 0.1500814 0.9347113 0.3245857 0.2017009 0.9241001 0.3236497 0.1495607 0.9342818 0.3309563 0.2103769 0.9198965 0.2219658 0.2219141 0.9494658 0.2163454 0.1693357 0.9615197 0.2214753 0.195263 0.9554167 0.2244538 0.1647921 0.96045 0.2644078 0.08839154 0.9603517 0.2292332 0.1126645 0.9668293 0.2398218 0.1785117 0.9542637 0.2170138 0.1312888 0.9672995 0.4709175 0.1191338 0.8740961 0.2384907 0.2049169 0.9492794 0.2334389 0.1291354 0.9637585 0.2226927 0.05642759 0.9732543 0.2205125 0.1112329 0.9690209 0.3467126 0.2044063 0.9154281 0.2793244 0.1085011 0.954047 0.4531057 0.1945125 0.8699771 0.3859508 0.1442999 0.9111639 0.2837194 0.06463599 0.9567266 0.2908923 0.1286597 0.9480656 0.3118082 0.04129236 0.9492474 0.2783721 0.1023436 0.9550051 0.5326634 0.1215896 0.8375475 0.5224129 0.1454675 0.8401929 0.5161282 0.04865211 0.8551285 0.3991833 0.03863173 0.9160569 0.5142016 0.0464785 0.8564091 0.5151611 0.1282042 0.8474508 0.390931 0.1245246 0.9119576 0.3880631 0.1174604 0.9141171 0.3867073 0.04959774 0.9208679 0.6174986 0.3368509 0.7107933 0.6607111 0.3933117 0.6393487 0.5933406 0.3675902 0.7161176 0.6434404 0.3330866 0.6892299 0.5091682 0.3892506 0.7676143 0.4720333 0.3294665 0.817702 0.5735315 0.2213008 0.7887253 0.6639342 0.288318 0.689974 0.5116267 0.3025441 0.8041798 0.5050129 0.2864854 0.8141795 0.3339002 0.2729331 0.9022296 0.3296716 0.2664106 0.9057274 0.4953675 0.2241922 0.839255 0.5243825 0.1735139 0.8336162 0.5041038 0.2557796 0.8248977 0.4953859 0.2402063 0.8348016 0 1 0 0 1 0 0 1 0 0 1 0 -0.1224583 0.037849 0.9917517 -0.3363393 0.0664972 0.9393903 -0.3233292 0.05916547 0.9444351 -0.5670589 0.05938416 0.8215338 -0.5490952 0.04770117 0.8343975 -0.7471503 0.06028395 0.6619158 -0.7681564 0.04397332 0.6387504 -0.8835169 0.066136 0.4637067 -0.9685137 0.07068639 0.2387149 -0.9261327 0.02614986 0.3762903 -0.9993869 0.03501528 0 -0.9702491 0.0377773 -0.2391433 -0.996609 0.06513243 0.05028229 -0.9794908 0.0612623 -0.19195 -0.8840476 0.05634564 -0.4639881 -0.7469246 0.0650829 -0.6617159 -0.8565611 0.0356028 -0.5148162 -0.567698 0.03596824 -0.8224508 -0.3544033 0.03361546 -0.9344883 -0.6294955 0.06686019 -0.7741224 -0.1205136 0.02018719 -0.9925065 -0.4633502 0.07571136 -0.8829351 -0.2655243 0.07687449 -0.9610344 -0.02132427 0.07076776 0.9972649 0.01386976 0.04142028 0.9990456 0.3254193 0.05351495 -0.9440544 0.5673907 0.04868948 -0.822008 0.325711 0.05344796 -0.9439575 0.5389199 0.05498218 -0.8405607 0.7473426 0.05591905 -0.6620818 0.712261 0.04984563 -0.7001426 0.8840632 0.05602461 -0.4639974 0.855823 0.04739594 -0.515093 0.9699244 0.04578775 -0.2390614 0.9744217 0.05066925 -0.2189404 0.9995274 0.03074061 0 0.9895781 0.06792688 0.1269693 0.9703378 0.03529065 0.2391638 0.9378327 0.06816697 0.3403281 0.8853786 0.01317703 0.464684 0.7918739 0.07997399 0.6054255 0.7482115 0.02840977 0.6628518 0.6416397 0.08117502 0.7626987 0.5675778 0.04135203 0.8222806 0.4930127 0.06956958 0.8672363 0.3542519 0.04448664 0.9340913 0.3131842 0.06052887 0.9477616 0.1202871 0.06413429 0.9906654 0.01454389 0.0474376 -0.9987683 0.01261669 0.0487591 -0.998731 0.9961601 0.08755099 0 0.9961935 0.08717 -1.59694e-4 0.9965301 0.06744247 -0.0487793 0.9954705 0.06952589 -0.06484383 0.994112 0.07889652 -0.07427507 0.6311544 0.1008994 0.7690666 0.6692773 0.007639169 0.7429736 0.7715545 0.06135898 0.6331973 -0.0247249 0.03492856 -0.9990839 0.8809378 0.04721671 0.4708708 -0.09487104 0.2512814 -0.9632534 0.7940471 0.02262562 0.6074351 -0.2819949 0.2372616 -0.9296159 0.9560171 0.04391753 0.2900046 -0.3260938 -0.1466924 -0.9338867 0.8950707 0.02489912 0.4452285 -0.4599419 0.2191103 -0.8604907 -0.4986713 -0.1266819 -0.8574839 0.994322 0.04162907 0.09793227 -0.6217075 0.1989644 -0.7575573 0.9652959 0.02766835 0.2596887 -0.6539226 -0.1046355 -0.7492908 -0.760837 0.1767652 -0.6244046 0.9945177 0.03660911 -0.09795159 -0.7859238 -0.0805431 -0.6130552 0.9964608 0.0333752 0.07714939 -0.871621 0.1523825 -0.4658933 -0.8894963 -0.0544213 -0.4536901 0.9959024 0.04390788 -0.07906019 -0.9493349 0.1258313 -0.2879754 -0.9604891 -0.02615451 -0.2770861 0.9560571 0.04295611 -0.2900167 0.9778872 0.03084409 -0.2068463 -0.990476 0.09716027 -0.09755635 -0.9959399 0.003946244 -0.08993512 0.8812824 0.03805196 -0.4710556 -0.9929952 0.0662949 0.09780424 0.9402322 0.03264737 -0.3389654 -0.9942858 0.03599029 0.1005008 0.8832323 0.03928065 -0.4672878 -0.9572648 0.03353995 0.287262 -0.9546767 0.06875562 0.2895948 0.7722973 0.04297101 -0.6338062 0.8097324 0.03218913 -0.5859158 -0.8859136 0.001553595 0.4638479 0.7200322 0.03066235 -0.6932629 -0.8775506 0.09942334 0.4690629 -0.7815562 -0.02843588 0.6231864 0.6051939 0.04520648 -0.7947937 -0.7666544 0.1279671 0.6291784 0.6341484 0.02766948 -0.7727162 -0.648417 -0.05644726 0.7591899 0.471182 0.03029918 -0.8815155 -0.6267909 0.154319 0.7637532 0.4549007 0.04102557 -0.8895968 -0.4917826 -0.08241969 0.8668085 0.2900674 0.03850871 -0.9562312 0.2900013 0.03855937 -0.9562492 -0.4638276 0.1784896 0.8677589 0.09795796 0.03477066 -0.994583 -0.3177455 -0.1063925 0.9421882 -0.2843844 0.2005764 0.9374939 0.09001022 0.05739301 -0.9942858 0.1150892 0.03128945 -0.9928622 -0.132954 -0.1282853 0.9827849 0.01378852 0.03484201 -0.9992978 -0.1429492 -0.1639446 -0.9760573 -0.09560346 0.2205849 0.9706711 0.055682 -0.1481403 0.9873976 0.09518694 0.238556 0.9664526 0.24123 -0.1659646 0.9561715 0.2807224 0.2545513 0.9254181 0.3719802 -0.007437884 0.9282109 0.4508845 0.140488 0.881457 0.4608215 0.210641 0.8621334 0.5332849 -0.02518397 0.8455609 0.8214123 0.5092027 0.2568942 0.8258278 0.500218 0.2603659 -0.5151504 0.7974679 -0.31411 -0.5227316 0.809201 -0.2682269 -0.5227321 0.809202 -0.2682228 -0.5283343 0.8443375 -0.08920252 -0.539169 0.8346468 -0.1125238 -0.5325773 0.8244423 -0.1914585 -0.5325773 0.8244423 -0.1914589 -0.3892735 0.8659061 -0.3141222 -0.3950017 0.8786506 -0.2682295 -0.3892734 0.8659056 -0.3141239 -0.849806 0.4906252 -0.1926573 -0.3950015 0.8786521 -0.2682242 -0.3996334 0.9119462 -0.09299147 -0.4024419 0.8952002 -0.1914601 -0.4075894 0.9066519 -0.1088721 -0.4024406 0.8952011 -0.191459 -0.254527 0.9146246 -0.3141302 -0.2545263 0.9146239 -0.314133 -0.1213642 0.9415361 -0.314294 -0.1086949 0.9597749 -0.2588776 -0.2582743 0.9280887 -0.2682271 -0.1142199 0.9565691 -0.2681964 -0.2582755 0.9280895 -0.2682235 -0.2631401 0.9455693 -0.1914578 -0.1108871 0.985805 -0.1260657 -0.2624952 0.9600386 -0.0970686 -0.1248978 0.9870589 -0.1005737 -0.2666186 0.9580737 -0.1049247 -0.2631389 0.9455692 -0.1914602 -0.1299418 0.97283 -0.1916169 -0.1124531 0.8977222 -0.4259687 -0.09458887 0.7707087 -0.6301277 -0.2396472 0.9708578 -0.002133548 -0.1252983 0.985258 -0.1164774 -0.8642253 0.4932165 -0.09925758 -0.8377832 0.5409236 -0.07430362 -0.8515601 0.4862828 -0.1958945 -0.8134571 0.5490456 -0.1919287 -0.8344293 0.5450804 -0.08133333 -0.8233266 0.5378237 -0.1813255 -0.7291018 0.6080616 -0.3141205 -0.6292924 0.710859 -0.314119 -0.7310391 0.6083347 -0.3090484 -0.7419902 0.6188082 -0.2579285 -0.7378534 0.6193533 -0.2682796 -0.7496159 0.656712 -0.08249598 -0.7537686 0.628631 -0.1914577 -0.7625231 0.6359375 -0.1189205 -0.7537657 0.6286325 -0.1914639 -0.6292936 0.7108644 -0.314104 -0.6385533 0.7213211 -0.2682268 -0.6385541 0.7213232 -0.2682192 -0.6458359 0.7586508 -0.08570271 -0.650581 0.7349064 -0.1914605 -0.6505797 0.7349075 -0.1914606 -0.658378 0.7437149 -0.1158734 -0.5151467 0.7974653 -0.3141228 0.002858638 0.3023992 -0.9531772 0.004234433 0.2762351 -0.9610808 9.83659e-4 0.285925 -0.9582515 0.04845005 0.270556 -0.9614843 0.03598415 0.2693929 -0.9623579 0.03526633 0.2682904 -0.9626923 0.04967963 0.2732586 -0.9606569 0.0506727 0.2425476 -0.9688152 0.564475 0.8240789 -0.04755967 0.5312156 0.8403012 -0.1081849 0.5276109 0.8345983 -0.1583437 0.5276099 0.8346009 -0.1583325 0.5999256 0.7672674 -0.2266942 0.6021505 0.7638933 -0.2321249 0.6479476 0.7457035 -0.1552106 0.6540634 0.7527498 -0.07462471 0.6130523 0.7840708 -0.09695428 0.6081643 0.7778193 -0.1585353 0.612725 0.7726897 -0.1658878 0.2784354 0.8573489 -0.4329282 0.6010851 0.7284708 -0.3286749 0.6793805 0.7324417 -0.04440093 0.4044042 0.8643804 -0.2988376 0.2928317 0.9148313 -0.2780887 0.3011067 0.905505 -0.2989908 0.2968377 0.9357386 -0.190475 0.3073642 0.9228787 -0.2319961 0.2464464 0.9687131 -0.02931278 0.2468664 0.9683939 -0.03564113 0.2538573 0.8027428 0.5395928 0.2695763 0.9578604 -0.09915757 0.5099297 0.8066372 -0.2988451 0.4044016 0.8643801 -0.298842 0.3101335 0.937402 -0.1584129 0.3033145 0.9473515 -0.1025942 0.4122163 0.8810878 -0.2318667 0.4122162 0.8810859 -0.2318739 0.3131236 0.9460411 -0.08342713 0.5099298 0.8066371 -0.2988449 0.5877442 0.751689 -0.2991995 0.4369981 0.8974368 -0.06033122 0.4219812 0.9019643 -0.09161037 0.4184175 0.8943464 -0.1583395 0.4184177 0.8943458 -0.1583425 0.5197858 0.8222286 -0.2318684 0.5197865 0.8222265 -0.2318741 0.1092326 0.07455462 -0.9912164 0.1544749 0.1016903 -0.9827496 0.1488119 0.09433448 -0.9843557 0.1136147 0.07610434 -0.9906058 0.117903 0.06648427 -0.9907971 0.202108 0.1843412 -0.9618579 0.1806429 0.08158224 -0.9801595 0.2584385 0.1150777 -0.959149 0.2247455 0.06780683 -0.9720554 0.2119538 0.0983203 -0.9723213 0.2073983 0.0922268 -0.9738995 0.2717725 0.09778261 -0.957381 0.2582803 0.07124233 -0.9634397 0.2053373 0.05489999 -0.9771503 0.2832927 0.05582213 -0.9574075 0.2472696 0.04093617 -0.9680816 0.2724753 0.03074741 -0.9616714 0.2506231 0.01551198 -0.9679605 0.2906502 0.02443641 -0.9565174 0.2339412 0.01973825 -0.9720504 0.2793657 -0.01241183 -0.9601047 0.2420521 -0.01406013 -0.9701614 0.287212 -0.01601338 -0.9577333 0.240148 -0.01342833 -0.9706435 0.2297317 -0.03922796 -0.9724631 0.284317 -0.05204951 -0.9573164 0.2713265 -0.05533236 -0.9608955 0.2384692 -0.04365688 -0.9701683 0.2243969 -0.06100243 -0.9725867 0.2788246 -0.07594293 -0.9573346 0.2674698 -0.09464538 -0.9589068 0.2630698 -0.09403324 -0.9601834 0.1903092 -0.07118254 -0.9791402 0.2171769 0.1872027 -0.9580133 0.1692853 0.1483456 -0.9743388 0.1863154 0.1466323 -0.9714863 0.2335613 0.1539201 -0.9600822 0.1200494 0.07171386 -0.9901744 0.1392074 0.1161466 -0.9834284 0.2446492 0.156385 -0.9569172 0.1949787 0.1244375 -0.9728817 0.1948347 0.1242579 -0.9729334 0.06832844 0.04228377 -0.9967665 0.2531433 0.1148487 -0.9605875 -0.7519676 -0.6519709 -0.09735977 -0.8196932 -0.5273154 -0.2237 -0.8196908 -0.5274016 -0.2235052 -0.8294931 -0.5338985 -0.1639937 -0.8295298 -0.533639 -0.1646511 0.8706308 -0.4763628 -0.1228038 -0.8771674 -0.4026149 -0.2616846 -0.8810509 -0.3475494 -0.3208723 -0.8400478 -0.5382785 -0.06764507 -0.8349035 -0.5417059 -0.09742122 -0.8360139 -0.5377749 -0.1089908 -0.8857396 -0.40655 -0.2240148 -0.8857583 -0.4066735 -0.2237163 -0.8964746 -0.4111297 -0.1652441 -0.8964744 -0.4116064 -0.1640549 -0.9516538 -0.2816113 -0.1226786 -0.9032374 -0.4149624 -0.1094005 -0.905968 -0.417907 -0.06764513 -0.9524316 -0.2882301 -0.09898275 -0.9060919 -0.4117489 -0.09726375 -0.9339901 -0.2775732 -0.2249791 -0.9256091 -0.2750822 -0.2599569 -0.9227567 -0.2116222 -0.322081 -0.934751 -0.2769235 -0.2226077 0.2550514 -0.852318 -0.4566211 -0.9524483 -0.05016124 -0.3005433 -0.8336536 -0.06276148 -0.5487102 0.193722 -0.5990428 -0.7769297 -0.9453701 -0.2818319 -0.1638482 -0.9450935 -0.2803925 -0.167864 -0.9728489 -0.1611952 -0.1660762 -0.96915 -0.04926383 -0.2414981 -0.9492548 -0.1567366 -0.2726703 -0.9614516 -0.1587491 -0.2245208 -0.9492604 -0.1317412 -0.2855682 -0.9566999 -0.05740666 -0.2853591 -0.9730921 -0.05514144 -0.2237209 -0.9618946 -0.158128 -0.2230571 -0.9841117 -0.05410486 -0.1691062 -0.9821434 -0.04949682 -0.1815061 -0.972447 -0.159628 -0.1698989 -0.201621 -0.4264765 -0.8817407 -0.9569129 -0.2815754 -0.07094305 -0.3585034 -0.9200219 -0.1582248 0.8485533 -0.4597815 -0.2618364 0.8353277 -0.4682934 -0.2879738 0.8505089 -0.4765412 -0.2225828 0.8607909 -0.4820064 -0.1634284 0.8740313 -0.4716084 -0.1168544 0.8081957 -0.5883873 -0.02490204 0.7907875 -0.602185 -0.1096741 0.8606991 -0.4973386 -0.1088655 0.7552914 -0.5886096 -0.2882251 0.7555194 -0.5885137 -0.2878233 0.7689604 -0.5989833 -0.2234257 0.7693473 -0.5988574 -0.2224292 0.7827256 -0.6096752 -0.1250472 0.7785886 -0.6060804 -0.1626852 0.7779572 -0.6063722 -0.1646069 0.7674658 -0.6315569 -0.110147 0.7262609 -0.6874189 6.36206e-4 0.6973447 -0.7082259 -0.1101208 0.6588906 -0.6950017 -0.2878122 0.658645 -0.6950641 -0.2882233 0.6706091 -0.7073634 -0.2234289 0.6705258 -0.7073767 -0.2236368 0.6821706 -0.7193973 -0.1308091 0.6785761 -0.7158673 -0.1645254 0.6786346 -0.715849 -0.1643636 0.6320579 -0.7748714 0.008801639 0.5885995 -0.8009402 -0.1097522 0.6655519 -0.7382588 -0.1096111 0.5474029 -0.7858213 -0.2878109 0.5471478 -0.7858463 -0.2882274 0.4265393 -0.8573485 -0.2881282 0.5572806 -0.7996399 -0.2236393 0.55703 -0.7996408 -0.2242591 0.5633302 -0.8094255 -0.1657997 0.5639585 -0.809332 -0.1641122 0.5667655 -0.813463 -0.1305946 0.4635578 -0.8792733 -0.1095106 0.5528382 -0.8260523 -0.109579 0.5274505 -0.8495857 -4.05075e-4 0.4186455 -0.8680523 -0.2668734 0.3736343 -0.8882014 -0.2673869 0.4358072 -0.8718245 -0.223594 0.4393236 -0.882725 -0.1667072 0.2037009 -0.9372804 -0.2828628 0.4389708 -0.8831409 -0.1654301 0.4421642 -0.8885717 -0.1221928 0.3629948 -0.9169586 -0.1655953 0.3441566 -0.9227842 -0.1732793 0.2278084 -0.9299762 -0.2885271 0.4340216 -0.894289 -0.1089605 0.371201 -0.9221189 -0.1091184 0.4140524 -0.9101071 -0.01630562 0.3429622 -0.9347574 -0.09276711 0.2319425 -0.9467497 -0.2233111 0.2668522 -0.9403315 -0.211108 0.1504397 -0.9456959 -0.2881445 0.2214179 -0.9613839 -0.163448 0.3239744 -0.9394534 -0.11166 0.1502752 -0.9458261 -0.2878031 0.1847053 -0.9820871 -0.03726851 0.3062964 -0.94578 -0.1080869 0.1661813 -0.9800537 -0.1089884 0.1533039 -0.9628134 -0.2224599 0.1529474 -0.9626469 -0.2234241 0.1544805 -0.9741867 -0.1646094 0.1550831 -0.9743802 -0.1628878 0.1557725 -0.9799973 -0.1238557 0.006962537 -0.9576653 -0.2877998 0.006735384 -0.9575378 -0.2882291 0.06192445 -0.998071 -0.004446566 0.1293057 -0.9855666 -0.109264 0.02718704 -0.9936075 -0.1095669 0.007020831 -0.9746478 -0.2236348 0.007086277 -0.9746922 -0.2234389 -0.2149009 -0.9343173 -0.2843744 -0.2444196 -0.8306109 -0.5003446 -0.2150458 -0.7073478 -0.6733606 0.00731188 -0.986446 -0.1639237 0.007098913 -0.9863436 -0.1645478 0.007328093 -0.991348 -0.131056 -0.2217688 -0.9318631 -0.2871406 -0.1369757 -0.947546 -0.2887809 -0.1365012 -0.9479117 -0.2878038 -0.06192481 -0.9980773 0.002656102 -0.1153249 -0.9872589 -0.1096363 -0.01709133 -0.9938516 -0.1093941 -0.2255972 -0.9478948 -0.2249476 -0.2458008 -0.9459251 -0.2116784 -0.1389038 -0.9645959 -0.2241889 -0.1387462 -0.964742 -0.2236573 -0.2193066 -0.9614204 -0.1660586 -0.1405302 -0.9763993 -0.1639992 -0.1409568 -0.976107 -0.1653673 -0.2754842 -0.9546868 -0.112613 -0.1412493 -0.9815228 -0.1290797 -0.1848101 -0.9826443 -0.01598906 -0.1574135 -0.9814733 -0.10923 -0.2657586 -0.9578936 -0.1086854 -0.4008952 -0.8776189 -0.2628084 -0.4158837 -0.8610423 -0.2926548 -0.4155663 -0.8818251 -0.2229108 -0.2925171 -0.9517016 -0.09326308 -0.4178258 -0.9074609 -0.04400622 -0.4143957 -0.894656 -0.1669337 -0.416324 -0.8946051 -0.1623459 -0.4199633 -0.9004346 -0.1133519 -0.5220384 -0.8059417 -0.2791668 -0.5287936 -0.7943171 -0.2990615 -0.4260872 -0.8995011 -0.09668248 -0.52955 -0.8186278 -0.2223182 -0.529837 -0.8179815 -0.2240068 -0.575172 -0.6268991 -0.5255233 -0.536211 -0.8282907 -0.1625192 -0.5367153 -0.8274771 -0.16498 -0.6352213 -0.717756 -0.2851672 -0.696468 -0.6583106 -0.2855864 -0.6316381 -0.7256963 -0.2727604 -0.6397017 -0.7349629 -0.2249696 -0.5401514 -0.8359675 -0.0969268 -0.5411056 -0.835062 -0.09937977 -0.6410816 -0.7347634 -0.2216692 -0.6476937 -0.7439556 -0.1643868 -0.6476166 -0.7441231 -0.1639324 -0.7400034 -0.5939193 -0.3156818 -0.7286371 -0.6302968 -0.2679814 -0.6532454 -0.7505951 -0.09938573 -0.6525614 -0.7514556 -0.0973556 -0.7371698 -0.637677 -0.2234922 -0.7371111 -0.6380609 -0.2225882 -0.746235 -0.6450814 -0.1643275 -0.7461199 -0.6454839 -0.1632655 -0.8197048 -0.4759112 -0.3187361 -0.8110473 -0.5218378 -0.2643632 -0.7525257 -0.6510197 -0.09939074 0.3153078 -0.1114248 0.9424253 0.2300161 -0.2374759 0.943768 0.3994372 -0.01494777 0.9166387 0.38689 -0.1579442 0.9084987 0.344882 -0.03913545 0.9378299 0.5281658 -0.2617605 0.8077886 0.5323675 -0.2606416 0.8053886 0.3999231 -0.01554656 0.9164169 0.2982953 -0.09068793 0.9501557 0.4499441 -0.2391257 0.8604472 0.2867745 -0.09771859 0.9530013 0.4523146 -0.2387928 0.8592959 0.3874842 -0.2200381 0.8952314 0.6204304 -0.436113 0.6518219 0.6397253 -0.3593965 0.6794009 0.2623467 -0.161288 0.9513993 0.6197323 -0.43531 0.6530216 0.2574205 -0.2600274 0.930656 0.2359846 -0.2275391 0.9447419 0.2331938 -0.1915581 0.9533762 0.5744743 -0.06320744 0.8160785 0.5147542 0.004073023 0.8573282 0.4667487 -0.03333562 0.8837617 0.604764 -0.3541819 0.7133133 0.3451961 -0.08965659 0.9342384 0.3346428 -0.09398317 0.9376468 0.289525 -0.137785 0.9472015 0.2651389 -0.1805074 0.9471634 0.3803406 -0.212971 0.8999913 0.4004461 -0.08831584 0.9120545 0.3903023 -0.09291762 0.9159861 0.5328261 -0.3208569 0.7830372 0.5128471 -0.3905391 0.7645044 0.5238145 -0.3216973 0.7887517 0.3272176 -0.1563321 0.9319275 0.5182051 -0.3965429 0.7577713 0.3367205 -0.1482278 0.9298645 0.3921064 -0.1546151 0.9068334 0.2646723 -0.07633966 0.9613121 0.2846947 -0.2385387 0.9284655 0.2832275 -0.1982091 0.9383471 0.3003665 -0.1923211 0.9342338 0.4573795 -0.09125506 0.8845772 0.5317134 -0.08832561 0.8423061 0.2992231 -0.1414417 0.9436418 0.4667088 -0.08651959 0.880169 0.3149882 -0.1326032 0.9397866 0.3870053 -0.1491783 0.9099301 0.4368332 -0.3532479 0.8272804 0.3835844 -0.3044462 0.8718805 0.4461329 -0.2907922 0.8464073 0.3497697 -0.273503 0.896023 0.3290224 -0.1940639 0.9241663 0.4425939 -0.2907065 0.8482926 0.3288908 -0.1941883 0.9241871 0.3320877 -0.2544167 0.9082896 0.5425757 -0.1647941 0.8236837 0.4692106 -0.1460476 0.8709258 0.4534672 -0.1546912 0.8777461 0.5322751 -0.1527655 0.832674 0.5372728 -0.1148809 0.8355481 0.4585748 -0.1495253 0.8759859 0.3732786 -0.3071562 0.875396 0.534627 -0.156143 0.830538 0.3747729 -0.2636129 0.8888496 0.3783825 -0.2629706 0.8875095 0.3845107 -0.2514806 0.8882055 0.4624296 -0.1389098 0.8757072 0.3827607 -0.2022457 0.9014383 0.4642081 -0.09401154 0.8807228 0.3885958 -0.198234 0.8998314 0.532396 -0.2418965 0.8111971 0.4754741 -0.2917297 0.8299508 0.2905631 -0.1767268 0.940394 0.5162628 -0.2028444 0.8320618 0.448238 -0.2633829 0.8542319 0.4542104 -0.1992634 0.8683242 0.4015976 -0.1026893 0.9100408 0.4474186 -0.2044945 0.8706312 0.6053482 -0.2245426 0.7636324 0.2542033 -0.03921228 0.9663556 0.2427178 -0.1182765 0.9628596 0.2544168 -0.1113311 0.9606651 0.2766054 -0.2601321 0.9251058 0.2923045 -0.2190921 0.9308904 0.28561 -0.2249951 0.93156 0.2879691 -0.277934 0.9164206 0.5326402 -0.2223282 0.8166178 0.6187709 -0.2832534 0.7327278 0.2367254 -0.1620342 0.9579698 0.2432638 -0.1436411 0.9592654 0.3996174 -0.1649193 0.9017248 0.2370711 -0.2019558 0.9502691 0.5331921 -0.1881185 0.8248137 0.3119881 -0.02328336 0.9498007 0.2971529 -0.04195946 0.9539076 0.4504603 -0.2626599 0.853285 0.6063668 -0.2830751 0.7430934 0.2395389 -0.0934751 0.9663765 0.2414661 -0.145924 0.9593749 0.3242785 -0.09828555 0.9408419 -0.8664259 0.4993059 -2.51617e-6 -0.8654479 0.5009986 7.06902e-4 -0.8295171 0.5584814 0 -0.8308569 0.5564856 -9.23941e-4 -0.9976179 0.06384503 0.02612352 -0.9976118 0.06394112 0.026124 -0.9813409 0.1904873 0.02616769 -0.9976173 0.06387311 0.02608019 -0.949053 0.3140258 0.02619946 -0.9812977 0.190724 0.02605986 -0.9489253 0.3144268 0.02601087 -0.9012434 0.4325176 0.02624857 -0.9009929 0.4330552 0.02598303 0.5807018 0.8141164 -1.99104e-6 0.5807058 0.8141136 1.09444e-6 0.5807188 0.8141043 -1.55094e-5 0.580703 0.8141155 4.05537e-7 -0.998332 -0.0560351 0.01390415 -0.9984945 -0.0548529 0 -0.9681774 -0.2498021 -0.01522088 -0.8915286 -0.4517884 -0.03262102 -0.9557214 -0.2922097 0.03478711 -0.7524359 -0.6579333 -0.03105038 -0.8635925 -0.5030666 0.03364682 -0.5667558 -0.8233792 -0.02889037 -0.716208 -0.6972416 0.03000646 -0.3461961 -0.9380534 -0.01429414 -0.5415884 -0.8406185 0.00652945 -0.1037886 -0.9943657 -0.02155965 -0.3159312 -0.948311 0.02989685 0.1449298 -0.989215 -0.02119231 -0.06818336 -0.9974335 0.02185362 0.3848084 -0.9229068 -0.01286756 0.1799045 -0.9834205 0.02276813 0.6008737 -0.7992771 -0.01035261 0.4056391 -0.9138976 0.0157569 0.6144384 -0.7888741 0.01196575 0.7799175 -0.6257974 0.01031678 0.7891568 -0.6140468 -0.01334828 0.9103515 -0.4136331 0.01295763 0.9140459 -0.4055985 -0.003164768 0.9843528 -0.1762064 9.34925e-4 0.98716 -0.1556531 -0.03587722 0.99864 -0.05170249 -0.006721317 0.9986295 -0.05233705 0 0.01322001 -0.9149124 -0.4034361 0.01407104 -0.9133012 -0.4070417 0.07145422 -0.9055262 -0.4182302 0.06712853 -0.9095958 -0.4100357 0.1287574 -0.9012635 -0.4136976 0.1265743 -0.9030573 -0.4104467 0.188271 -0.8939685 -0.4066626 0.190815 -0.8968468 -0.3990684 0.2476249 -0.8859215 -0.3922053 0.2401673 -0.8893446 -0.3890833 0.2660619 -0.8914889 -0.3666862 0.300971 -0.8830271 -0.3601105 0.3016019 -0.8916039 -0.3377558 0.3451772 -0.8833486 -0.3170932 0.3423369 -0.8918452 -0.295665 0.3819888 -0.8835045 -0.2711172 0.373336 -0.8953464 -0.2428482 0.4116192 -0.8848133 -0.2183466 0.3983324 -0.8978832 -0.1874489 0.4293464 -0.8889872 -0.159259 0.4099039 -0.9027137 -0.1307171 0.4352972 -0.8949491 -0.09789067 0.4285499 -0.9026495 -0.03960931 0.4105089 -0.9089183 -0.07314443 0.4079999 -0.9129818 4.47817e-4 0.4006206 -0.9161007 -0.01621031 0.395771 -0.9178436 0.03047275 0.3950517 -0.9181432 0.03077989 0.3817749 -0.9222119 0.06142729 0.385253 -0.9197008 0.07570183 0.3596724 -0.929097 0.08610802 0.3483396 -0.9299186 0.1179452 0.3453272 -0.9310748 0.1176812 0.3165594 -0.9389136 0.1350241 0.3102003 -0.9367085 0.1623364 0.2932114 -0.9427727 0.1587668 0.4414569 -0.03479939 0.8966075 0.4184056 -0.04459482 0.9071649 0.583987 -0.04110562 0.8107217 0.5121667 -0.0314179 0.8583114 0.6144568 -0.0332961 0.7882477 0.7081364 -0.0364564 0.705134 0.8084464 -0.035905 0.5874737 0.7176483 -0.03378784 0.6955857 0.891824 -0.03533536 0.4510006 0.8134887 -0.03427779 0.5805698 0.9517484 -0.03512597 0.3048627 0.8941106 -0.0344482 0.4465193 0.9871046 -0.03527355 0.1561423 0.9533562 -0.03428107 0.2998946 0.9993132 -0.03554928 0.01046353 0.988475 -0.03399568 0.147518 0.9878762 -0.03634315 -0.1509299 0.999426 -0.03357553 -0.004521548 0.9410326 -0.03472161 -0.3365297 0.9864292 -0.0347926 -0.1604593 0.9411957 -0.0348277 -0.3360622 0.985731 -0.05621182 -0.1586655 0.9566231 -0.01725292 -0.2908174 0.8590136 -0.03483694 -0.5107662 0.8590156 -0.03483611 -0.5107628 0.9326857 -0.1099051 -0.3435381 0.749933 -0.03479427 -0.6605982 0.7500205 -0.03476989 -0.6605001 0.9047551 0.01277112 -0.425741 0.8558936 -0.09492832 -0.508365 0.6157902 -0.0347833 -0.7871421 0.6108304 -0.03590148 -0.7909471 0.8310672 -0.003545701 -0.5561609 0.7434397 -0.07811993 -0.6642248 0.4435676 -0.03476804 -0.8955664 0.4492369 -0.03348594 -0.892785 0.2545277 -0.03462767 -0.9664454 0.2545338 -0.0346263 -0.9664438 0.058627 -0.03478991 -0.9976736 0.05520117 -0.03556859 -0.9978415 -0.1401243 -0.03612816 -0.9894746 -0.1312851 -0.03395396 -0.990763 -0.4711431 -0.03478902 -0.8813705 -0.3115783 -0.03336137 -0.9496347 -0.3189535 -0.03557235 -0.9471026 -0.4735003 -0.03389781 -0.8801412 -1.7932e-4 -0.0262196 -0.9996562 5.35606e-6 -0.02617341 -0.9996575 -1.22753e-6 -0.02617621 -0.9996573 0 -0.02617692 -0.9996574 -3.18425e-5 -0.02622073 -0.9996563 2.1497e-5 -0.02609294 -0.9996596 2.63021e-6 -0.02618241 -0.9996573 -1.93143e-5 -0.02616399 -0.9996577 -3.7313e-6 -0.02617508 -0.9996575 0 -0.02617931 -0.9996573 1.34743e-5 -0.0261752 -0.9996574 3.29661e-4 -0.02611875 -0.9996589 0.713231 0.665272 0.220714 0.7112665 0.6680219 0.2187393 1 -8.1534e-6 1.14846e-6 1 6.46287e-6 -9.10339e-7 -2.81081e-6 -0.02617341 -0.9996575 -3.82672e-6 -0.02612978 -0.9996586 -2.47181e-6 -0.02618992 -0.999657 -2.96182e-6 -0.02614921 -0.9996581 0 -0.02616178 -0.9996578 8.69116e-7 -0.02615863 -0.9996578 0 -0.02620375 -0.9996566 -1.07288e-6 -0.02617657 -0.9996574 9.53935e-7 -0.02624326 -0.9996557 0 -0.02619475 -0.9996569 6.76831e-6 -0.02617061 -0.9996576 0 -0.02616566 -0.9996576 6.83411e-6 -0.02617704 -0.9996574 0 1 -7.05438e-7 0 1 8.05297e-6 0 1 -2.50511e-5 0 1 3.68489e-5 4.59841e-6 1 -2.46154e-5 -1.56784e-4 1 2.5178e-4 -3.7054e-5 1 -1.44994e-5 2.4272e-6 1 0 1.58735e-6 1 0 1.13244e-6 1 0 -1.03639e-6 1 0 3.00054e-5 1 -7.69862e-6 3.35245e-7 1 0 8.40598e-7 1 0 0 1 1.12871e-5 0 1 -3.68492e-5 0 1 2.50509e-5 0 1 -5.88814e-7 0 1 5.85274e-7 0 1 0 0 1 2.17593e-7 0 1 2.90453e-7 0 1 -8.70386e-7 0 1 -3.01659e-7 0 1 2.18982e-7 0 1 -2.37318e-6 0 1 5.7575e-7 0 1 8.19309e-7 0 1 0 0 1 2.37681e-6 0 1 1.42462e-7 0 1 -1.66951e-7 0 1 -7.86825e-7 0 1 -2.37319e-6 0 1 2.79102e-7 0 1 1.39007e-7 0 1 -9.34343e-7 0 1 -4.60682e-7 0 1 0 0 1 -9.10993e-7 -0.5334057 0.2382015 0.8116271 -0.7113586 0.2344732 0.6625642 -0.7072615 0.6708595 0.2229995 -0.7291172 0.6095234 0.3112385 -0.4156892 0.144665 0.8979279 -0.7414867 0.4545783 0.493514 -0.5453183 0.4753149 0.6904374 -0.3662239 0.2712665 0.8901093 -0.1536774 0.1019533 0.9828473 -0.4289652 0.7592777 0.4893733 -0.4417404 0.2158745 0.8707835 -0.8960735 0.320612 0.3070182 -0.995131 0.09854495 -0.001812219 -0.9925673 0.121576 -0.005425214 -0.9921697 0.1245545 -0.009239912 -0.997471 0.07093584 0.004450738 -0.1728486 0.7838677 -0.5963848 -0.3619477 0.6158551 -0.6997974 -0.467044 0.8143359 -0.3445681 0 0 1 2.03595e-6 0 1 3.02343e-6 0 1 -3.54054e-6 0 1 7.59558e-6 0 1 -1.60264e-5 0 1 6.61947e-6 0 1 -8.78784e-6 0 1 3.34851e-6 0 1 1.19032e-5 0 1 -3.9067e-6 0 1 -8.30875e-6 0 1 -9.21192e-5 0 1 1.83816e-5 0 1 -1.2641e-5 0 1 3.20547e-6 0 1 2.32717e-4 -0.002261221 0.9999974 -0.002442538 -0.0208221 0.9997802 1.29213e-6 0 1 -1.30818e-6 0 1 6.44673e-7 0 1 -6.44961e-7 0 1 -6.52771e-7 0 1 0 0 1 1.57655e-7 0 1 -7.35558e-7 0 1 0.03615611 5.86808e-4 0.9993461 -6.05876e-5 -1.42582e-5 1 -3.25076e-7 0 1 0 3.29957e-4 1 -3.20361e-4 2.95027e-4 1 3.55333e-5 -1.70315e-4 1 -6.22059e-4 3.10813e-4 0.9999998 -2.1369e-4 1.45366e-4 1 4.77339e-5 1.88241e-4 1 9.38197e-5 -1.68899e-4 1 -8.42034e-5 1.50355e-4 1 -3.19713e-5 -1.2271e-5 1 -1.96095e-6 0 1 -3.26584e-5 -2.21831e-5 1 -2.86689e-5 -2.57229e-5 1 6.3978e-7 0 1 -2.61665e-5 -2.92742e-5 1 3.31331e-7 0 1 3.80713e-5 -1.0418e-4 1 -1.30544e-5 -2.93151e-5 1 -1.32756e-4 2.93422e-5 1 -1.55817e-4 5.86887e-5 1 -6.33999e-7 0 1 -3.15811e-7 0 1 6.15304e-7 0 1 2.76328e-6 0 1 -1.78161e-7 0 1 1.78161e-7 0 1 1.25991e-6 0 1 -6.15304e-7 0 1 -1.04588e-6 0 1 0 0 1 1.30696e-6 0 1 -7.33039e-7 0 1 -1.8318e-7 0 1 -7.31663e-7 0 1 1.30605e-6 0 1 -1.83022e-7 0 1 0.6599009 0.5877887 -0.4680122 0.5112475 0.4979723 -0.7004639 0.7130488 0.5793764 -0.3948221 0.9410437 0.2140527 -0.2619512 0.7361621 0.5326535 -0.4175473 0.6447653 0.3717034 -0.6679179 0.6961852 0.347705 -0.6280345 0.2417947 0.3009605 -0.922474 0.3746951 0.4579718 -0.8061423 0.2479027 0.2476292 -0.9366024 0.299247 0.2629947 -0.9172159 0.5490764 0.2342342 -0.8022777 0.4159741 0.2774004 -0.8660338 0.4166992 0.2260653 -0.8804864 0.666632 0.2083788 -0.7156676 0.8621326 0.1729868 -0.4762384 0.6702007 0.2086008 -0.7122617 0.9979013 0.06226128 -0.01779568 0.9171871 0.1383715 -0.3736594 0.00429207 0.6889546 -0.7247919 0.0311439 0.6515567 -0.7579604 0.02873158 0.4321122 -0.901362 0.01201784 0.4528934 -0.8914837 0.004783511 0.987977 -0.1545274 0.002413153 0.8628191 -0.5055072 0.003979504 0.9854539 -0.1698962 0.002542316 0.987846 -0.1554154 0.02105194 0.8575404 -0.5139858 0.02036768 0.788607 -0.6145603 0.007790088 0.78859 -0.6148701 -0.1251798 0.2821252 -0.9511758 -0.3872175 0.2707763 -0.8813303 -0.2607335 0.2692608 -0.9271012 -0.5359029 0.2459502 -0.8076612 -0.6665906 0.2292826 -0.7092859 -0.6975304 0.2301415 -0.6785914 -0.8574862 0.1789708 -0.4823763 -0.8714867 0.1783713 -0.4568312 -0.9849197 0.09455233 -0.1448898 -0.9826325 0.09585177 -0.1588895 -0.5470616 0.4188352 -0.7247765 -0.2114485 0.3618444 -0.9079418 -0.8349879 0.2891896 -0.4681502 -0.7482697 0.3700783 -0.5505765 -0.4598987 0.3541446 -0.814294 -0.8102043 0.5277594 -0.255028 -0.6544724 0.6343966 -0.4113475 -0.4533623 0.5713714 -0.6841033 -0.4332578 0.5127867 -0.7411732 -0.1039893 0.4037985 -0.9089187 -0.7511234 0.3684101 -0.5478026 -0.8528515 0.452096 -0.261254 -0.2436045 0.3893076 -0.888311 -0.9585576 0.2590848 -0.1185012 0.8730301 0.4821972 0.07283121 0.9064687 0.3668125 0.2091965 0.7638804 0.4236065 0.4868719 0.7484474 0.3845698 0.5403079 0.3820144 0.1492286 0.9120285 0.6019137 0.3615132 0.7120451 0.4619026 0.08305001 0.8830339 0.7280131 0.6526831 0.2097662 0.6993407 0.6911473 0.1823128 0.5356826 0.652776 0.5356565 0 0.7071073 0.7071064 0 0.7071078 0.7071058 4.02833e-4 0.9999998 5.7164e-4 1.61914e-4 0.9999997 -8.3438e-4 0 1 0 0.0700547 0.7165826 -0.6939753 0.06729185 0.7184409 -0.6923255 0.1052092 0.7505277 -0.6524103 0.1377973 0.7490231 -0.6480557 0.1243655 0.7575764 -0.6407896 0.1535314 0.7859002 -0.59899 0.346833 0.4645035 -0.8148273 0.5061876 0.6821148 -0.5277249 0.5391188 0.7118067 -0.4502024 0.5704234 0.7047221 -0.4218815 0.9946187 0.1036012 6.63583e-4 0.9955874 0.09380686 -0.00247544 0.9958077 0.09147197 1.3749e-4 0.999639 0.001170992 0.02684211 0.4673323 -0.8809134 0.07478076 0.3381407 -0.9375991 0.08104848 0.4479505 -0.8912755 0.07048755 0.1323338 -0.9872232 0.08875989 0.149762 -0.9809404 0.1238042 0.1361856 -0.9870868 0.08434033 0.2775817 -0.9563131 0.09172618 0.2275272 -0.9371671 0.2644793 0.4153396 -0.9095928 0.01158285 0.4153085 -0.909571 0.01412731 0.2346549 -0.9645025 0.1211285 0.1001666 -0.990249 0.09681856 0.2345662 -0.9579333 0.1653559 0.007924437 -0.9955444 0.09396058 0.8738883 -0.4703468 -0.1228546 0.8809269 -0.464725 -0.08943545 0.8024087 -0.5834514 -0.1253986 0.7644973 -0.6446269 -2.857e-4 0.8310459 -0.5561949 -0.003169417 0.8686383 -0.4822182 -0.1137242 0.8352807 -0.4578642 -0.304412 0.8225275 -0.5054683 -0.2606732 0.8584524 -0.476599 -0.189507 0.7738004 -0.6058639 -0.1848294 0.829469 -0.5550988 -0.06202155 0.7823033 -0.6127365 -0.1120513 0.7642524 -0.6441601 -0.03124403 0.6977817 -0.7139231 -0.05843502 0.6987251 -0.7147931 -0.02922624 0.7817617 -0.5748357 -0.2416871 0.6899675 -0.7104209 -0.1387339 0.7382455 -0.6321578 -0.2353086 0.7547857 -0.6466814 -0.1100088 0.6018748 -0.7985255 0.01019543 0.6185776 -0.7856559 0.01033848 0.5312845 -0.8463271 -0.0383048 0.6520109 -0.746293 -0.1338977 0.6975875 -0.7136877 -0.06341755 0.6544526 -0.7492694 -0.1014261 0.571645 -0.8204832 -0.005424857 0.6186534 -0.7856613 -0.00209254 0.571047 -0.8192471 -0.05234146 0.5201356 -0.024217 -0.8537403 0.5058002 -0.05269873 -0.8610395 0.5248265 -0.02893579 -0.8507174 0.5054813 0.05359965 -0.8611712 0.5215953 0.02595621 -0.8527982 0.5246282 0.02891099 -0.8508405 0.7724398 0.6350317 0.008454799 0.7559418 0.6535564 -0.03763318 0.6975162 0.7163622 -0.01721698 0.6993914 0.7145714 0.0154742 0.63632 0.771274 -0.01527923 0.5044732 0.8617131 -0.05438184 0.6519531 0.755038 -0.06982016 0.6967927 0.7154276 -0.05141472 0.2354421 0.9576846 0.1655516 0.6019696 0.7970479 0.0484513 0.468635 0.8817929 0.05312842 0.5397779 0.8415446 0.02103966 0.008012354 0.9955438 0.09396004 0.1000084 0.9902656 0.09681135 0.5786678 0.8145146 -0.04134827 0.6363382 0.7714086 0.001648545 0.5789883 0.815326 0.004038214 0.483188 0.8754694 0.00909388 0.5389992 0.8406278 0.0531485 0.4831377 0.8754338 0.01391988 0.1683126 0.979548 0.1102579 0.3388194 0.9367569 0.08768248 0.144436 0.9853373 0.09082251 0.3751249 0.9221088 0.09485137 0.09285312 0.9900887 0.1053696 0.2135478 0.9761346 -0.0394802 0.2096369 0.9637557 0.1650072 0.3234295 0.9364941 0.1355451 0.3254052 0.943188 0.06714189 0.3737962 0.9192643 0.1234093 0.9990481 0.02618837 0.03488916 0.9990485 0.02617496 0.03488636 0.9990485 0.02617347 0.03488731 0.9990484 0.02618163 0.03488737 0.9990938 0.02543729 0.03412824 0.9990485 0.02617716 0.03488415 0.9990485 0.02617561 0.03488391 0.9902683 -0.1391721 7.08302e-7 0.9902681 -0.1391734 1.2915e-7 0.9902681 -0.1391735 0 0.9902832 -0.139066 -1.75116e-4 0.001897513 -0.1420378 -0.9898595 -0.001260161 -0.1388201 -0.9903168 -0.008769571 -0.1397244 -0.9901517 -0.9902681 -0.1391728 3.09341e-4 -0.9902368 -0.1393953 1.05742e-6 -0.9902994 -0.1389502 -2.89061e-4 -0.9902685 -0.1391706 0 0.2164416 -0.9762956 9.90937e-7 0.2164399 -0.976296 0 0.2164404 -0.9762959 -1.62172e-6 0.2164394 -0.976296 -1.59577e-6 0.2164391 -0.9762961 1.48869e-6 0.9902681 -0.1391735 1.24144e-4 0.9903154 -0.138835 -4.38566e-4 0.9902813 -0.1390796 -1.18894e-4 0.9902555 -0.1392625 1.535e-6 -0.001466095 -0.1425716 -0.9897834 -0.002366721 -0.1427665 -0.9897536 0.002150893 -0.1388819 -0.9903067 -0.9902683 -0.1391721 7.08302e-7 -0.9902681 -0.1391735 0 -0.9902681 -0.1391733 0 -0.9902922 -0.1390017 -2.80741e-4 0 1 0 0 1 0 0.2712491 -0.04088968 0.9616404 0.2911564 -0.03477108 0.9560434 0.06239116 -0.0443412 0.9970664 0.1229507 -0.03011077 0.9919559 -0.1390596 -0.04252564 0.9893706 -0.06778371 -0.02520215 0.9973817 -0.3342522 -0.04405808 0.9414534 -0.2733973 -0.02594244 0.9615513 -0.4206445 -0.03217524 0.9066548 -0.5157449 -0.04133611 0.8557444 -0.5124651 -0.04022461 0.8577656 -0.6766456 -0.04476642 0.7349467 -0.6327779 -0.0280053 0.7738268 -0.8099068 -0.04343903 0.584948 -0.7669913 -0.02644622 0.6411123 -0.9065763 -0.04209017 0.419938 -0.8788272 -0.02490544 0.4764899 -0.9721992 -0.04467856 0.2298533 -0.9556855 -0.02761727 0.2930916 -0.998629 -0.04312044 0.02967852 -0.9938539 -0.02664494 0.1074456 -0.9841944 -0.04464954 -0.1713708 -0.9963074 -0.02680212 -0.08156722 -0.930028 -0.0425809 -0.3650134 -0.9627996 -0.02697348 -0.2688671 -0.8430792 -0.03537732 -0.5366246 -0.9120838 -0.03451293 -0.4085487 -0.8624899 -0.04721659 -0.503867 -0.7327553 -0.03727602 -0.6794705 -0.8062652 -0.03343462 -0.5906087 -0.7389749 -0.03940361 -0.6725798 -0.6654433 -0.03289502 -0.7457233 -0.6084929 -0.0397911 -0.7925611 -0.5832473 -0.03485077 -0.8115468 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0.02345234 -0.9997251 0 0.02742236 -0.9996171 0.003703773 -0.1956986 -0.9806581 -0.003448247 -0.4090077 -0.9125065 -0.006679236 -0.2073975 -0.9782322 0.006937146 -0.6017862 -0.7985977 -0.009754538 -0.4271174 -0.9041398 0.01011443 -0.7643924 -0.6446267 -0.01267337 -0.6238897 -0.7814013 0.01317632 -0.888618 -0.4583855 -0.01551848 -0.7870848 -0.6166348 0.01609694 -0.9680396 -0.249038 -0.02965909 -0.9108121 -0.4120882 0.02459174 0.1391732 -0.9902681 0 0.1391724 -0.9902682 2.40352e-6 -0.9802263 -0.1908361 0.05232465 -0.9816057 -0.1804502 0.06235343 -0.9920008 -0.1086473 0.06426733 -0.9890813 -0.1398929 0.04634827 -0.994894 -0.08851182 0.04849314 -0.9976534 -0.03628987 0.05805754 -0.9981436 -0.03141731 0.05217784 -0.9981381 -0.03137058 0.05231028 -0.9902674 -0.1391779 0 -0.9882459 -0.1479293 0.03856235 0.7163603 -0.152099 -0.6809508 0.6277168 0.1447051 -0.7648739 0.8394844 -0.146535 -0.5232527 0.7654271 0.1397134 -0.6281734 0.9285571 -0.1396964 -0.3438993 0.8740317 0.1334595 -0.4671799 -0.0980165 0 0.9951848 -0.1011483 -0.01986473 0.9946731 0.979874 -0.1315811 -0.1501116 0.9493191 0.1259576 -0.2879725 -0.2991411 -0.03842443 0.953435 -0.2902327 0.01922243 0.956763 0.9912338 -0.1221826 0.05027019 0.9883293 0.1171741 -0.09734195 -0.4845489 -0.05567103 0.872991 -0.4710726 0.03716427 0.8813112 0.9620409 -0.1114987 0.2490892 0.9894605 0.1071027 0.09745335 -0.6497012 -0.07159942 0.7568104 -0.6334758 0.05378115 0.7718912 0.8933475 -0.09952127 0.4382075 0.9525458 0.09572941 0.2889508 -0.7878305 -0.08623653 0.6098248 -0.7711625 0.06908416 0.632879 0.7878299 -0.08623045 0.6098267 0.8788745 0.08304935 0.4697686 -0.8933475 -0.09951138 0.4382098 -0.8788753 0.08304941 0.469767 0.6497011 -0.07160139 0.7568102 0.7711627 0.06908005 0.6328791 0.4845488 -0.05566501 0.8729913 -0.962037 -0.1115419 0.2490851 -0.9525433 0.09574556 0.2889536 0.6334756 0.05378931 0.7718909 0.2991414 -0.0384252 0.9534349 -0.9894628 0.1070824 0.09745204 0.4710728 0.03715604 0.8813115 -0.9912312 -0.1222031 0.05027306 0.1011483 -0.0198642 0.994673 0.2902327 0.01922452 0.9567631 -0.9883285 0.1171822 -0.09734034 -0.9798713 -0.1316005 -0.1501117 0.09801632 0 0.9951848 -0.9493201 0.1259414 -0.2879759 -0.928559 -0.139675 -0.3439027 -0.8740336 0.1334517 -0.4671788 -0.8394838 -0.1465468 -0.5232504 -0.7654266 0.1397215 -0.628172 -0.7163609 -0.1520932 -0.6809514 -0.6277168 0.1447051 -0.7648739 -0.5642344 -0.1564362 -0.8106586 -0.4661766 0.1484176 -0.8721535 -0.3893054 -0.1595411 -0.9071869 -0.2869613 0.1509013 -0.9459821 -0.198659 -0.1614003 -0.9666875 0 -0.1620146 -0.9867885 -0.09687656 0.1521355 -0.9836004 0.198659 -0.1613969 -0.966688 0.09687638 0.1521342 -0.9836006 0.3893052 -0.159541 -0.9071869 0.2869613 0.1508993 -0.9459823 0.5642336 -0.1564419 -0.810658 0.4661763 0.1484216 -0.8721529 -0.04393327 0.9988821 -0.01745545 -0.1667115 0.1217778 0.9784567 -0.5125377 0.4028006 0.758325 -0.1407637 0.1825499 0.9730679 -0.8349391 0.3697438 0.4076352 -0.7522339 0.5164044 0.4092317 -0.7468444 0.5206255 0.4137302 -0.3112909 0.5088241 0.8026183 -0.318261 0.5103778 0.7988895 -0.1538342 0.6024429 0.7831971 -0.5256746 0.7649447 0.3721906 -0.4778026 0.7735284 0.4163635 -0.1530918 0.9210591 0.3580687 -0.1966427 0.8941484 0.4022816 -0.8077515 0.5892512 0.0179032 -0.6257715 0.7463787 -0.2265591 -0.8141592 0.5617011 -0.1470946 -0.9423384 0.3267194 -0.07247567 -0.9857868 0.1654278 -0.02929234 -0.9105991 0.4039645 -0.08730435 -0.8056032 0.5756603 -0.1400668 -0.7068343 0.6945974 -0.1338647 -0.6200447 0.7255389 0.29856 -0.719812 0.6801377 -0.1388648 -0.7451432 0.6587114 -0.1042157 -0.6737722 0.7328176 -0.09491783 -0.836094 0.5420117 -0.08467787 -0.8496168 0.525031 -0.04993939 -0.9869187 0.16086 -0.01075249 -0.6764157 0.7203034 -0.153704 -0.9559658 0.292393 -0.02521926 -0.8359493 0.5423347 -0.08403533 -0.9558166 0.2927123 -0.02709835 -0.6506435 0.7537335 0.09246116 -1.15317e-6 -1 0 -5.54468e-6 -1 0 -2.07854e-6 -1 0 -2.82798e-7 -1 0 8.35077e-6 -1 7.51398e-7 6.50829e-6 -1 4.51967e-5 -8.15609e-6 -1 -1.01767e-6 -5.37267e-6 -1 0 0 -1 -3.08191e-6 -6.0975e-6 -1 2.6465e-5 9.78046e-6 -1 2.21307e-6 7.09569e-6 -1 -9.62851e-6 -1.56161e-5 -1 0 -6.53205e-6 -1 8.86368e-6 -1.47758e-5 -1 -1.2696e-6 3.77828e-6 -1 -8.38741e-6 -1.41735e-5 -1 -4.82184e-6 8.26762e-6 -1 -7.01421e-6 -8.429e-6 -1 -9.65149e-6 3.22743e-6 -1 0 2.87714e-6 -1 -3.62455e-6 -7.67655e-6 -1 -9.34374e-6 6.51897e-6 -1 1.98369e-5 0 -1 1.97077e-6 2.47114e-7 -1 -8.09945e-6 -1.9945e-6 -1 -3.00277e-6 1.46581e-5 -1 -1.21976e-6 6.03597e-6 -1 0 1.74705e-6 -1 0 6.97812e-6 -1 -1.7993e-6 0 -1 1.75793e-6 -8.59425e-6 -1 2.65712e-6 0 -1 1.54093e-6 -1.48617e-5 -1 0 -1.53479e-6 -1 3.26312e-6 5.35216e-5 -1 0 -7.60363e-7 -1 0 -3.12737e-6 -1 -1.29927e-6 0 -1 -1.54096e-6 8.43847e-6 -1 -4.2802e-5 6.97993e-6 -1 -1.2021e-5 -8.53374e-7 -1 -9.38998e-6 0 -1 -1.67896e-6 1.48613e-5 -1 -6.18334e-7 -2.9797e-6 -1 0 7.30822e-6 -1 9.91685e-6 -6.03595e-6 -1 0 1.17391e-5 -1 -1.23419e-5 -6.03597e-6 -1 0 -6.69116e-6 -1 -9.07958e-6 2.44987e-5 -1 -5.10105e-6 6.50829e-6 -1 2.25984e-5 -6.09752e-6 -1 2.11721e-5 7.09567e-6 -1 -9.62848e-6 -6.53203e-6 -1 8.8636e-6 3.22747e-6 -1 5.36331e-6 3.66067e-5 -1 -3.35397e-6 -2.73751e-5 -1 4.23887e-6 1.06997e-5 -1 -1.65678e-6 3.86537e-6 -1 0 0 -1 3.22357e-6 1 1.27238e-6 -4.95184e-6 1 0 2.98022e-5 0.4375926 0.0827592 0.8953568 0.04187071 -0.006393074 0.9991027 0.4420496 0.02958059 0.8965028 0.3641349 0.03486549 0.9306935 0.6927698 0.04626899 0.719673 0.8929587 0.05708265 0.4465049 0.7512044 0.06082433 0.6572613 0.9905717 0.05743962 0.1243728 0.9574102 0.07090902 0.2798888 0.6828511 0.3622794 0.6344038 0.7140026 0.3465538 0.6083591 0.3931532 0.2240968 0.8917461 0.3105521 0.9340009 0.1766346 0.1778608 0.9183955 0.3534339 0.2114894 0.770711 0.6010631 0.6680854 0.7215619 0.1816878 0.5765511 0.7635437 0.2908435 0.4087972 0.630189 0.6601112 0.4774139 0.6322827 0.6101595 0.8850323 0.390899 0.2528163 0.8615064 0.4160141 0.2910996 0.3257132 0.3536357 0.8768426 0.2441269 0.3232238 0.9142912 -0.001063466 0.1536631 0.9881227 0.001726329 0.3498411 0.9368075 -6.69497e-4 0.5624916 0.8268029 0.001715719 0.6919628 0.721931 -8.91856e-4 0.9479226 0.3184999 -6.41334e-4 0.9449387 0.3272467 -0.4640955 0.8842604 0.05195176 -0.4640927 0.8842614 0.05196011 -0.2390012 0.9696283 0.05195623 -0.2390018 0.9696283 0.05195444 0.9913643 -0.1203998 0.05196988 0 0.9986495 0.05195277 0.9913721 -0.1203458 0.05194634 0 0.9986495 0.05195373 0.9337608 -0.3541073 0.05195075 0.238996 0.9696294 0.05195921 0.9337469 -0.3541416 0.05196887 0.2389943 0.9696301 0.05195605 0.8218815 -0.5672848 0.05194884 0.4641023 0.8842564 0.05195981 0.8218693 -0.5673024 0.05195075 0.4641109 0.8842518 0.05196267 0.6621918 -0.7475306 0.05196195 0.6622062 0.7475187 0.0519495 0.6622302 -0.7474975 0.05194997 0.6622214 0.7475045 0.05196148 0.4641023 -0.8842564 0.05196118 0.8218746 0.5672948 0.05195116 0.4641113 -0.8842515 0.0519616 0.8218753 0.5672939 0.05194818 0.9337599 0.3541069 0.05196899 0.2389985 -0.9696289 0.0519582 0.9337469 0.3541439 0.05195069 0.2389861 -0.9696319 0.05195796 0.9913669 0.1203891 0.0519461 0.9913695 0.1203565 0.05196952 0 -0.9986495 0.05195486 0 -0.9986495 0.05195575 -0.2389972 -0.9696293 0.05195486 -0.2390005 -0.9696285 0.05195629 -0.4641044 -0.8842552 0.05195969 -0.464084 -0.8842664 0.05195283 -0.6622248 -0.7475015 0.05196177 -0.6622191 -0.7475064 0.05196177 -0.821859 -0.5673174 0.05195122 -0.8218747 -0.5672935 0.05196285 -0.9337583 -0.3541139 0.05195051 -0.9337571 -0.3541169 0.05195224 -0.9913679 -0.1203776 0.0519523 -0.9913653 -0.1204 0.05194896 -0.9913651 0.1204006 0.05195248 -0.9913681 0.1203775 0.05194896 -0.9337573 0.3541166 0.05195224 -0.9337573 0.3541169 0.05195021 -0.8218654 0.5673069 0.05196338 -0.8218693 0.5673024 0.05195087 -0.6622279 0.7474988 0.0519616 -0.6622191 0.7475064 0.0519616 0.2393161 -0.9709417 0 0.2393147 -0.9709421 0 -0.9927089 0.1205368 0 -0.2393161 -0.9709417 0 -0.2393147 -0.9709421 0 -0.9350163 0.3546047 0 -0.464724 -0.8854556 0 -0.4647226 -0.8854565 0 -0.9350163 0.3546049 0 -0.6631233 -0.7485103 0 -0.8229835 0.5680654 0 -0.6631219 -0.7485114 0 -0.8229849 0.5680632 0 -0.8229847 -0.5680636 0 -0.8229838 -0.5680651 0 -0.6631222 0.7485112 0 -0.663123 0.7485105 0 -0.9350161 -0.3546056 0 -0.9350166 -0.3546041 0 -0.4647225 0.8854565 0 -0.464724 0.8854556 0 -0.9927089 -0.1205368 0 -0.2393147 0.9709421 0 -0.2393161 0.9709417 0 0.2393147 0.9709421 0 0.2393161 0.9709417 0 0.4647226 0.8854565 0 0.464724 0.8854556 0 0.6631219 0.7485114 0 0.6631233 0.7485103 0 0.8229847 0.5680636 0 0.8229838 0.5680651 0 0.9350166 0.3546041 0 0.9350161 0.3546056 0 0.9927089 0.1205368 0 0.9927089 -0.1205368 0 0.9350163 -0.3546049 0 0.9350163 -0.3546047 0 0.8229849 -0.5680632 0 0.8229835 -0.5680654 0 0.663123 -0.7485105 0 0.6631222 -0.7485112 0 0.464724 -0.8854556 0 0.4647225 -0.8854565 0 0.9109919 0.4076556 -0.06253683 0.8353892 0.5458704 -0.06442409 0.7717692 0.6358072 0.01103317 0.755402 0.6516342 -0.06885272 0.9216679 0.3861339 -0.0378012 0.9316765 0.3614141 -0.03686314 0.7313016 0.6459566 -0.2189477 0.7285166 0.6759178 -0.1113494 0.9454119 0.3184643 -0.06911551 0.7438757 0.6432236 -0.1814178 0.934392 0.3376693 -0.1135386 0.6566684 0.711993 -0.2487021 0.895922 0.4020913 -0.188803 0.8788313 0.3423485 -0.332345 0.8500256 0.5001443 -0.1652642 0.3332436 0.9264691 -0.1749399 0.3307086 0.9267718 -0.1781173 0.6909687 0.7123365 -0.1230404 0.2992453 0.8442312 -0.4446639 0.9069836 0.3929378 -0.1515944 0.7364854 0.6416305 -0.2142416 0.3867742 0.7448034 -0.5437589 0.6839102 0.5944862 -0.4229104 0.3211973 0.6166216 -0.718756 0.3023196 0.6129695 -0.7299803 0.8511081 0.2735297 -0.4481033 0.7285429 0.4471667 -0.5189097 0.5691237 0.3764465 -0.7310172 0.997886 0.0648936 -0.00353527 0.9982405 0.05927485 -0.001523017 0.9982322 0.05941772 -0.001458525 -0.9116889 0.3886929 -0.1331957 -0.9204041 0.3551005 -0.1635849 -0.6763399 0.728519 -0.1087405 -0.7357143 0.6408534 -0.2191607 -0.8439684 0.3086938 -0.4386634 -0.3182797 0.9291943 -0.1878726 -0.6877518 0.5978458 -0.4117984 -0.7321774 0.4477381 -0.5132709 -0.636519 0.3812346 -0.6704505 -0.3270035 0.9284229 -0.1763513 -0.3819027 0.7510991 -0.538517 -0.2978975 0.8496696 -0.4351078 -0.4773552 0.4405749 -0.7602801 -0.3207375 0.6281903 -0.7088754 -0.2250359 0.6200563 -0.751591 -7.57329e-4 0.9999997 4.07716e-4 -3.05055e-4 0.9999997 6.79739e-4 1.05545e-4 0.9999994 0.001088261 -8.3817e-4 0.9999997 3.81051e-4 -4.75358e-6 1 0 -2.68982e-6 1 1.02277e-5 -9.74358e-7 1 -4.39423e-5 -1.43158e-6 1 -1.75937e-6 -4.41778e-7 1 5.8181e-6 -3.05502e-6 1 -1.98834e-7 0 1 8.11134e-7 0 1 7.50503e-7 0 1 -5.45518e-7 -0.001124024 0.9999988 -0.001125633 -0.002387225 0.9999971 -3.28484e-4 -0.002086162 0.9999978 -4.58671e-4 -3.62535e-4 0.9999979 -0.002058923 -3.40829e-5 0.9999996 9.06931e-4 0 1 -4.04144e-5 -1.32067e-4 1 1.86665e-4 0.004347205 0.9999317 -0.0108574 7.53358e-7 1 1.13213e-5 5.51948e-7 1 3.99431e-6 0 1 -1.76152e-5 0 1 4.62733e-6 6.33295e-4 0.9999982 0.001795828 -7.74109e-4 0.9999852 0.005393207 9.37362e-5 0.9999964 0.002732932 0.00116676 0.9999988 0.001079797 0.002079367 0.9999977 5.55652e-4 -8.59476e-6 1 0 1.46581e-5 1 1.21976e-6 0 1 -2.66427e-6 0 1 -1.92812e-6 -3.94371e-6 1 5.9025e-6 6.41099e-7 1 0 -3.06425e-7 1 -2.71826e-6 8.81058e-6 1 -3.31026e-6 -8.15575e-6 1 2.03524e-6 0 1 2.71083e-7 0 1 1.54094e-6 9.78091e-6 1 2.21314e-6 -1.56159e-5 1 0 6.07367e-7 1 0 5.55387e-7 1 -1.8294e-5 0 1 1.20355e-6 0 1 3.46175e-5 -1.35735e-5 0.9999973 -0.002343416 4.63183e-4 0.9999964 -0.002668261 9.34712e-4 0.9999986 -0.001433849 0.00124973 0.9999988 -0.001005113 0.002062976 0.9999979 -4.60346e-4 -0.002583265 0.9998823 -0.01513087 0.003740906 0.999993 4.28742e-5 0.001054167 0.9999994 -2.35237e-4 0.00368154 0.9999933 1.27466e-4 9.62456e-5 0.999994 -0.003499448 -0.992879 0.1186943 0.01014947 -0.9982798 0.05818909 -0.007180392 -0.9998261 0.01812726 -0.004378139 1.21372e-5 4.9363e-6 1 0 9.81617e-6 1 0 5.24031e-6 1 2.92089e-6 0 1 -2.03581e-5 3.25715e-7 1 -1.15271e-6 0 -1 2.89213e-6 0 -1 -4.67536e-5 0 1 0.9993909 -0.03489935 -6.00793e-6 0.999391 -0.03489816 0 0.9371457 -0.03744888 -0.3469229 0.9384475 -0.03643262 -0.3434953 0.7636138 -0.03396672 -0.6447793 0.757032 -0.03568625 -0.6524027 0.7636111 0.03397506 -0.644782 0.7513988 0.0371381 -0.6588025 0.999391 0.03489816 0 0.9993909 0.03489947 -5.99792e-6 0.9384485 0.0364322 -0.3434928 0.9369868 0.03757327 -0.3473386 6.3637e-5 7.06403e-4 -0.9999998 0 0.001164913 -0.9999994 3.15096e-4 0 -1 -1.77501e-6 0 -1 1.19956e-5 0 -1 0.7071071 0 0.7071065 0.7071064 0 0.7071073 0.7071066 0 -0.7071071 0.7071066 0 -0.707107 -0.7071068 0 -0.7071068 -0.7071064 0 -0.7071073 -0.7071066 0 0.7071071 -0.7071068 0 0.7071067 0 1 1.39116e-6 0 1 9.47065e-7 0 1 3.456e-6 0 1 3.18565e-6 0 1 -5.9599e-6 0 1 1.14803e-6 0 1 -1.61066e-6 0 1 -1.20687e-6 0 1 7.78758e-7 0 1 3.10441e-6 -3.40609e-7 1 1.38513e-6 0 1 -3.15571e-7 2.60383e-7 1 0 -3.46497e-7 1 0 0 1 -2.19321e-6 0 1 -2.86262e-6 0 1 -5.18731e-6 0 1 6.41877e-6 -9.77745e-7 1 2.27891e-7 0 1 -2.21135e-6 0 1 -3.27204e-6 -3.15521e-6 1 -2.05315e-6 1.22616e-6 1 0 0 1 -5.50312e-7 0 1 1.13389e-6 0 1 3.22132e-6 0 1 -1.18428e-6 0 1 2.97995e-6 0 1 6.91181e-6 0 1 -3.18565e-6 -1.28825e-6 1 0 0 1 -4.10374e-6 -1.64798e-6 1 -1.83288e-6 0 1 -1.14803e-6 0 1 2.0705e-6 0 1 1.61107e-6 0 1 -2.44686e-6 -1.22614e-6 1 -1.1334e-6 3.15517e-6 1 0 -1.18495e-6 1 0 0 1 0 9.77782e-7 1 0 0 1 5.1873e-6 0 1 7.17133e-7 0 1 1.45587e-7 0 1 -5.72531e-6 0 1 2.19321e-6 0 1 2.86262e-6 2.95374e-6 1 0 0 1 -6.41877e-6 0 1 6.04219e-6 1.39869e-6 1 -1.82783e-7 8.47973e-7 1 1.76664e-6 0 1 1.5751e-6 0 1 -1.13389e-6 0 1 1.33564e-6 0 1 -2.7606e-6 0 1 1.18428e-6 0 1 5.05071e-6 0 1 -6.91181e-6 -0.9367946 0.349555 -0.01508063 -0.9842502 0.1762607 -0.01356226 -0.5452786 0.8382459 0.00389713 -0.28377 0.9574275 -0.05298328 -0.3771008 0.9260629 -0.01423394 -0.1352177 0.989324 0.05435377 -0.7507752 0.6602506 -0.02014857 -0.8324865 0.5539658 -0.009393095 -0.954563 0.2979527 -0.005806863 0.03247469 0.9994726 1.13853e-4 -0.9922706 0.1240915 6.81422e-4 -0.9900873 0.1403399 0.005662918 -0.9247944 0.2029275 -0.3218321 -0.926535 0.1999745 -0.3186584 0.9071737 -0.002493143 0.4207491 0.9987944 -0.002493202 0.0490278 -0.1745742 0.00901556 -0.9846028 0.9998259 0.009316205 -0.01616901 0.9630851 -0.008958041 -0.2690481 -0.3397815 -0.01356053 -0.9404067 -0.542455 0.008957982 -0.8400372 0.8750652 0.01414746 -0.4837983 0.7626802 -0.01414614 -0.6466211 -0.7836161 0.00406444 -0.6212322 -0.7339231 -0.008922457 -0.679174 0.5549547 0.01355874 -0.8317701 0.1690654 0.005909442 -0.9855871 0.4051148 -0.009016752 -0.9142214 -0.9758982 0.004769086 -0.218174 -0.9655035 -0.004768431 -0.2603469 0.07174247 -0.005908787 -0.9974057 -0.9655049 0.004768431 0.2603414 -0.9758995 -0.004767894 0.2181683 -0.7339233 0.008923888 0.6791738 -0.7836132 -0.00406444 0.6212359 -0.5424554 -0.008958041 0.8400368 -0.3341668 0.01414686 0.9424079 -0.1420698 -0.01414585 0.9897556 0.1420695 0.01414585 0.9897557 0.3341675 -0.01414734 0.9424075 0.5809014 0.01355963 0.813861 0.7111679 -0.009016871 0.7029645 0.8806194 0.008243441 0.4737529 0.9071606 -0.005909442 0.4207431 0.9825235 0.009015619 0.1859204 0.9987555 -0.009183168 0.04902434 -0.1745774 0.009014785 -0.9846022 0.9631007 0.006750047 -0.2690567 0.9655047 0.004769086 -0.2603421 -0.3397864 -0.0135613 -0.9404048 -0.5424457 0.008958041 -0.8400433 0.7627472 -0.00476849 -0.6466793 -0.7836139 0.004063308 -0.621235 0.7685453 -0.00675106 -0.6397599 -0.7339296 -0.00892353 -0.6791669 0.5269926 0.009182333 -0.8498203 0.1690727 0.005909323 -0.9855859 0.4051171 -0.009016036 -0.9142205 -0.9758989 0.004769086 -0.2181711 -0.9655024 -0.004769146 -0.2603508 0.0717436 -0.005908608 -0.9974056 -0.9655044 0.00476855 0.2603435 -0.9758995 -0.004769146 0.2181686 -0.7685667 0 0.6397698 -0.7836257 -0.004065096 0.6212201 -0.5222487 0.00406444 0.8527836 -0.5424916 0 0.8400614 -0.142072 -0.004768669 0.9898449 -0.09897142 0.004768908 0.9950789 0.3341823 -0.004768788 0.9424964 0.3256638 -0.006753146 0.9454615 0.6076917 0.009184062 0.79412 0.7111724 -0.009016752 0.70296 0.8615848 0.005910098 0.5075793 0.9071648 -0.005910217 0.4207342 0.982523 0.009015321 0.1859226 0.9987553 -0.009183168 0.04902642 -0.1745737 0.009015381 -0.9846029 0.9631015 0.006751477 -0.2690539 0.9655031 0.004769682 -0.2603482 -0.3397807 -0.01356112 -0.9404069 -0.5424565 0.00895822 -0.8400361 0.7627479 -0.004769146 -0.6466784 -0.7836179 0.00406444 -0.62123 0.7685464 -0.006749451 -0.6397585 -0.733922 -0.008922457 -0.6791753 0.5270006 0.009182333 -0.8498153 0.169067 0.005909681 -0.9855868 0.4051148 -0.009016335 -0.9142214 -0.9758989 0.004769682 -0.2181711 -0.965504 -0.004767835 -0.2603448 0.07174247 -0.005908668 -0.9974057 -0.9655037 0.00476861 0.2603459 -0.9759004 -0.004770278 0.2181648 -0.7339209 0.008923888 0.6791765 -0.783625 -0.004063546 0.621221 -0.5424563 -0.008958041 0.8400364 -0.3341668 0.01414746 0.9424079 0.1420698 0.01414585 0.9897556 0.3341676 -0.01414704 0.9424076 0.5809124 0.01356005 0.8138533 0.7111619 -0.009016931 0.7029705 0.8615842 0.005910694 0.5075804 0.9655038 -0.004769146 0.2603451 0.9758996 0.004769146 0.218168 -0.09896421 -0.004769027 -0.9950796 -0.1420662 0.004767417 -0.9898458 0.975898 -0.004769146 -0.2181752 0.9655042 0.004768431 -0.2603443 -0.5809381 0.007910609 -0.8139094 -0.5222515 -0.004064679 -0.8527819 0.7627443 -0.004769086 -0.6466826 0.7339431 0.004769682 -0.6791943 -0.8615672 0.0102542 -0.5075401 -0.7685415 -0.007583141 -0.6397551 0.3341942 0.004769265 -0.9424922 0.3748317 -0.004769504 -0.9270806 -0.9815031 0.002492487 -0.1914303 -0.9669026 -0.009316325 -0.2549761 -0.9733389 0.002471506 0.2293589 -0.9684386 -0.002471566 0.2492404 -0.7376836 0.009316921 0.6750824 -0.7801404 -0.002492189 0.6255996 -0.5269923 -0.01025503 0.8498083 -0.3831587 0.007582902 0.9236514 -0.1361816 -0.007912158 0.9906524 -0.06614249 0.004064083 0.9978019 0.3341823 -0.00476849 0.9424964 0.3747978 0.004769384 0.9270944 0.7339527 -0.004768848 0.6791839 0.7627467 0.004768908 0.6466797 0.94933 0.3142765 -0.001716136 0.9291408 0.3697257 5.01699e-4 0.6964999 0.7175568 -4.29838e-4 0.6804724 0.7327736 4.2539e-4 0.3402075 0.9403504 -3.98223e-4 0.2911688 0.9566706 0.001519024 -5.51357e-5 0 1 1.87447e-5 0 1 5.51327e-5 0 1 -4.82637e-6 0 1 7.72584e-7 0 1 -2.31315e-6 0 1 -1.10265e-4 0 1 -2.27083e-6 0 1 -1.33924e-5 0 1 -3.51644e-6 0 1 3.78846e-6 0 1 -6.69623e-6 0 1 2.27617e-6 0 1 -1.33925e-5 0 1 -1.67405e-6 0 1 -1.33925e-5 0 1 -2.50854e-6 0 1 -3.6756e-7 0 1 1.51006e-6 0 1 -0.9816823 0.1905066 0.002673447 -0.8360211 0.5486897 0.002888977 -0.9198743 0.3922021 -0.003004789 -0.4690293 0.8831814 0.001458168 -0.6801761 0.7330402 -0.003546714 -0.1609584 0.9869579 0.002551615 -0.3225498 0.9465489 -0.002596259 0.8901365 0.008242964 -0.4556196 0.9825228 -0.00901556 -0.1859241 0.9987554 0.009183049 -0.04902368 -0.1745706 -0.009014368 0.9846034 0.9631016 -0.00675261 0.2690535 0.9655035 -0.00476861 0.2603464 -0.339779 0.01356035 0.9404076 -0.5424578 -0.008957922 0.8400353 0.7627469 0.004769265 0.6466796 -0.7836235 -0.004063546 0.6212228 0.7685499 0.006752252 0.6397542 -0.7339221 0.00892508 0.6791751 0.5270157 -0.009182333 0.849806 0.1690893 -0.005910336 0.9855831 0.4050945 0.009016156 0.9142305 -0.9759002 -0.004769146 0.2181652 -0.9655035 0.004769742 0.2603462 0.07171684 0.00590974 0.9974076 -0.9655038 -0.004769086 -0.2603453 -0.9758993 0.004769086 -0.2181695 -0.7339249 -0.008922755 -0.679172 -0.7836179 0.004063665 -0.62123 -0.5424531 0.00895971 -0.8400384 -0.3341786 -0.01414698 -0.9424036 -0.1745595 0.009456098 -0.9846013 0.1510002 -0.006750822 -0.9885107 0.1420736 -0.004768729 -0.9898446 0.5546584 0.0048877 -0.8320638 0.5809568 -0.002474546 -0.8139308 0.8615993 -0.002494037 -0.5075829 0.8901374 0.008242964 -0.4556177 0.9825226 -0.00901556 -0.1859248 0.9987555 0.009183526 -0.04902434 -0.1745928 -0.009014725 0.9845995 0.963102 -0.006752192 0.2690519 0.9655044 -0.00476861 0.2603431 -0.3397538 0.01355916 0.9404168 -0.5424617 -0.008958756 0.8400328 0.762749 0.004769146 0.646677 -0.7836221 -0.004063904 0.6212247 0.7685523 0.006752133 0.6397515 -0.7339273 0.008924961 0.6791694 0.526997 -0.009183764 0.8498175 0.1690642 -0.005910336 0.9855874 0.4051091 0.00901544 0.9142239 -0.9759005 -0.004769146 0.218164 -0.9655042 0.004769206 0.2603442 0.07172966 0.00590974 0.9974067 -0.9655053 -0.004768431 -0.2603403 -0.9758988 0.004769146 -0.2181718 -0.7339394 -0.004770278 -0.6791982 -0.7627432 0.00476849 -0.6466841 -0.3748309 0.004769682 -0.9270809 -0.3341942 -0.004769146 -0.9424922 0.09895509 0.004768908 -0.9950805 0.142076 -0.004768788 -0.9898443 0.5546606 0.004887044 -0.8320625 0.5809527 -0.00247544 -0.8139336 0.8616019 -0.002493381 -0.5075787 0.8901741 -0.004320204 -0.4556002 0.9998293 0.009654939 -0.01576066 -0.3697956 -0.002441525 0.9291099 0.9764648 -0.01035577 0.2154284 -0.2899526 0.007308542 0.9570132 0.8782584 0.009696841 0.4780881 -0.762742 -0.002384603 0.6466986 0.708177 -0.01251882 0.705924 -0.7339164 0.002384543 0.6792357 0.1726309 -0.0105192 0.9849304 0.3833057 0.01447993 0.923508 -0.9759077 -0.002384424 0.2181711 -0.9655124 0.002384722 0.2603464 -0.9522912 -0.007503092 -0.3050988 -0.9759069 0.002384185 -0.2181747 -0.7627131 0.009651541 -0.646665 -0.580452 -0.009697318 -0.8142368 -0.3749236 0.007072329 -0.9270288 -0.09886598 -0.007070899 -0.9950757 0.09882813 0.007073044 -0.9950794 0.4089852 -0.008886635 -0.9124978 0.5546007 0.007168531 -0.8320859 0.8800752 -0.007592856 -0.4747739 0.9975615 0.0141434 -0.06834477 -0.3697941 -0.002441942 0.9291106 0.9764641 -0.01035541 0.2154314 -0.2899587 0.007308185 0.9570114 0.8782584 0.009696722 0.4780881 -0.7627575 -0.00238496 0.6466803 0.7081921 -0.01251876 0.7059089 -0.7339392 0.002383947 0.679211 0.172645 -0.01051908 0.984928 0.3832924 0.01447969 0.9235135 -0.975908 -0.002384603 0.2181695 -0.9655106 0.002384781 0.2603527 -0.9522919 -0.007503151 -0.3050966 -0.975907 0.002384603 -0.218174 -0.7627127 0.009650707 -0.6466655 -0.5804322 -0.009698927 -0.8142508 -0.374947 0.007070243 -0.9270193 -0.098809 -0.007071375 -0.9950814 0.1355537 0.009701609 -0.9907225 0.4089828 -0.01251405 -0.9124563 0.7276006 0.014485 -0.6858481 0.8800048 -0.01518428 -0.4747222 0 1 -1.61688e-7 0 -1 -3.23376e-7 0 -1 0 -0.08369529 -0.001717567 -0.99649 -0.06975668 0 -0.9975641 0.06975668 0 -0.997564 0.06975406 0 -0.9975642 0.139177 0 -0.9902675 0.1391745 0 -0.9902679 0.20791 0 -0.978148 0.2079074 0 -0.9781486 0.2756407 0 -0.9612608 0.2756358 0 -0.9612622 0.3420213 0 -0.9396923 0.3420236 0 -0.9396914 0.4067363 0 -0.9135456 0.4067385 0 -0.9135447 0.4694712 0 -0.8829478 0.4694733 0 -0.8829467 0.5299143 0 -0.8480512 0.5299161 0 -0.8480502 0.5877848 0 -0.8090174 0.5877864 0 -0.8090162 0.6427845 0 -0.7660471 0.6427838 0 -0.7660478 0.6946652 0 -0.7193332 0.6946632 0 -0.7193352 0.7431409 0 -0.669135 0.7431392 0 -0.669137 0.7880111 0 -0.6156612 0.7880105 0 -0.6156618 0.8290373 0 -0.5591933 0.8660238 0 -0.5000028 0.8660235 0 -0.5000033 0.8987983 0 -0.4383626 0.9048371 0.001717329 -0.4257546 0.9271831 -0.001713633 -0.3746048 0.9466431 0.001717448 -0.3222792 0.9552823 -0.001717269 -0.2956908 0.9702929 0.001713573 -0.2419278 0.9822842 -0.001717507 -0.1873899 0.9848091 0 -0.173641 0.9945207 0 -0.1045402 0.9993912 0 -0.03489166 0.9997798 0.001717209 -0.02091813 0.9993897 -0.001714229 0.0348916 0.9958832 0.001716732 0.09063029 0.9929605 -0.001717567 0.1184347 0.9848077 0.001713633 0.1736407 0.9735794 -0.001718282 0.2283424 0.9702942 0 0.2419281 0.9510566 0 0.309017 0.9510566 0 0.309017 0.9271844 0 0.3746053 0.9271844 0 0.3746057 0.8987985 0 0.4383621 0.8987982 0 0.4383627 0.8660235 0 0.5000033 0.8660238 0 0.5000028 0.8290373 0 0.5591933 0.7880105 0 0.6156617 0.7880111 0 0.6156612 0.7431392 0 0.6691369 0.7431409 0 0.669135 0.6946632 0 0.7193352 0.6946652 0 0.7193332 0.6427838 0 0.7660478 0.6427845 0 0.7660472 0.5877866 0 0.8090162 0.5877847 0 0.8090175 0.5299162 0 0.8480501 0.5180097 0.001717388 0.8553731 0.4694685 -0.001713275 0.8829476 0.4194684 0.001716971 0.9077684 0.4067363 0 0.9135456 0.3420236 0 0.9396914 0.3420213 0 0.9396923 0.2756358 0 0.9612622 0.2621732 -0.001717448 0.9650194 0.2079097 0.001713454 0.9781466 0.1530053 -0.001717627 0.9882239 0.139177 0 0.9902676 0.06975406 0 0.9975642 0.06975668 0 0.9975641 -0.06975668 0 0.997564 -0.08369356 0.001717567 0.9964901 -0.1391743 -0.001713216 0.9902665 -0.1942157 0.001717686 0.9809573 -0.2215627 -0.001717746 0.9751446 -0.2756403 0.001713275 0.9612594 -0.3288487 -0.001717627 0.9443811 -0.3420236 0 0.9396914 -0.4067363 0 0.9135456 -0.4067385 0 0.9135447 -0.4694712 0 0.8829478 -0.4694733 0 0.8829467 -0.5299143 0 0.8480512 -0.5417183 0.001717686 0.8405584 -0.5877839 -0.001713275 0.8090162 -0.6320121 0.001717567 0.7749568 -0.6534276 -0.001717388 0.756987 -0.6946647 0.001712977 0.7193316 -0.7337123 -0.001718103 0.679458 -0.7431403 0 0.6691358 -0.78801 0 0.6156625 -0.7880094 0 0.6156632 -0.8290394 0 0.5591902 -0.8367742 0.001717627 0.5475456 -0.8660247 -0.001713097 0.4999984 -0.892577 0.001717209 0.4508917 -0.8987941 0 0.4383712 -0.927184 0 0.3746065 -0.927184 0 0.3746064 -0.9510563 0 0.309018 -0.9552822 -0.001717627 0.2956909 -0.9702944 0.001713275 0.2419213 -0.9822826 -0.001717627 0.1873977 -0.9848079 0 0.1736476 -0.994522 0 0.104528 -0.994522 0 0.104528 -0.9993908 0 0.03490066 -0.9993908 0 0.03490066 -0.9993908 0 -0.03490066 -0.9993908 0 -0.03490066 -0.994522 0 -0.104528 -0.994522 0 -0.104528 -0.984808 0 -0.1736475 -0.9848079 0 -0.1736476 -0.9702959 0 -0.2419217 -0.9702959 0 -0.2419217 -0.9510563 0 -0.309018 -0.9510563 0 -0.309018 -0.927184 0 -0.3746063 -0.9271839 0 -0.3746066 -0.8987941 0 -0.4383712 -0.8987938 0 -0.4383717 -0.866026 0 -0.4999992 -0.8660262 0 -0.4999986 -0.8290394 0 -0.5591902 -0.8290393 0 -0.5591904 -0.7880095 0 -0.6156632 -0.7880099 0 -0.6156626 -0.7431403 0 -0.6691358 -0.743142 0 -0.6691337 -0.6946638 0 -0.7193346 -0.6946657 0 -0.7193328 -0.6427832 0 -0.7660482 -0.6427839 0 -0.7660476 -0.5877866 0 -0.8090162 -0.5877847 0 -0.8090175 -0.5299162 0 -0.8480501 -0.5299142 0 -0.8480514 -0.4694733 0 -0.8829467 -0.4694712 0 -0.8829478 -0.4067385 0 -0.9135447 -0.4067363 0 -0.9135456 -0.3420236 0 -0.9396914 -0.3288502 0.001717627 -0.9443805 -0.2756379 -0.001713395 -0.96126 -0.2215627 0.001717746 -0.9751446 -0.194214 -0.001717746 -0.9809577 -0.1391743 0.001713216 -0.9902665 0 -1 1.4758e-5 0 -1 -2.36697e-6 0 -1 -2.97994e-6 0 -1 -3.93447e-6 0 -1 -1.70133e-6 0 -1 5.17193e-6 0 -1 2.15176e-7 0 -1 -2.77917e-5 0 -1 1.192e-5 0 -1 -9.93795e-5 0 -1 5.17187e-6 0 -1 4.96894e-5 0 -1 -7.49266e-6 0 -1 2.15179e-7 0 -1 1.23462e-6 0 -1 1.39638e-6 0 -1 -7.79162e-6 0 -1 -1.22691e-6 0 -1 2.15902e-5 0 -1 -8.0823e-7 0 -1 -1.93993e-6 0 -1 1.35156e-6 0 -1 3.79964e-6 0 1 -1.22887e-6 0 1 2.77923e-5 0 1 -1.79146e-6 0 1 -7.79145e-6 0 1 -7.49311e-6 0 1 -2.13463e-6 0 1 1.79147e-6 0 1 2.92493e-6 0 1 7.79137e-6 0 1 -4.31786e-5 0 1 -3.48477e-6 0 1 -1.55836e-5 0 1 3.02716e-6 0 1 4.31836e-5 0 1 3.27472e-5 0 1 1.19491e-5 0 1 -1.69469e-6 -1.74659e-6 0 1 -0.07497918 -0.9971851 0 -0.07497876 -0.9971852 -2.61459e-7 -1.32818e-6 0 1 -0.07497835 0.9971852 -1.96094e-7 -0.07497876 0.9971852 0 -1.30994e-6 0 1 0 1 1.1736e-6 0 1 2.46692e-6 0 1 -1.17239e-6 0 1 1.1743e-6 0 1 -1.17455e-6 0 1 -1.17073e-6 0 1 -5.86194e-7 0 1 -1.17361e-6 0 1 -1.17239e-6 0 1 3.92449e-7 0 1 -1.56198e-6 0 1 1.17072e-6 0 1 6.16725e-7 0 1 6.21893e-7 0 1 -5.86799e-7 0 1 6.13828e-7 0 1 7.85993e-7 0 1 5.86205e-7 0 1 -1.23167e-6 0 1 -1.84573e-6 0 1 1.84484e-6 0 1 -5.85368e-7 0 1 2.92681e-7 0 1 -1.84484e-6 0 1 1.53811e-7 0 1 5.89485e-7 0 1 -2.30938e-7 0 1 1.85018e-6 0 1 -1.85018e-6 0 1 3.07471e-7 0 1 2.30938e-7 0 1 -5.86808e-7 0 1 6.15245e-7 0 1 -1.53811e-7 0 1 1.84484e-6 0 1 5.8537e-7 0 1 3.08362e-7 0 1 6.16724e-7 0 1 -1.84484e-6 0 1 1.23956e-6 0 1 1.84573e-6 0 1 -6.14429e-7 0 1 6.15833e-7 0 1 -2.34479e-6 0 1 1.85019e-6 0 1 5.87273e-7 0 1 -1.17072e-6 0 1 -6.16725e-7 0 1 -5.87152e-7 0 1 1.17239e-6 0 1 1.17361e-6 0 1 5.86194e-7 0 1 1.17073e-6 0 1 -1.17455e-6 0 1 -2.46692e-6 0 1 5.87152e-7 0 1 -6.1525e-7 0 1 1.17239e-6 0 1 1.23167e-6 0 1 5.86799e-7 0 1 2.46098e-6 0 1 -8.80197e-7 0 1 -5.86205e-7 0 1 2.9358e-7 0 1 3.92545e-7 0 1 -1.46819e-6 0 1 -1.22707e-6 0 1 2.05504e-6 0 1 5.86797e-7 0 1 -6.15251e-7 0 1 0 0 1 2.93577e-7 0 1 -3.07471e-7 0 1 1.71716e-7 0 1 -6.15245e-7 0 1 -4.39649e-7 0 1 5.86808e-7 0 1 -5.86797e-7 0 1 -3.08362e-7 0 1 -2.05504e-6 0 1 -5.8537e-7 0 1 3.92817e-7 0 1 -6.16724e-7 0 1 6.15836e-7 0 1 -1.1724e-6 0 1 2.46332e-6 0 1 -3.9195e-7 -0.4886238 0 -0.8724946 -0.488627 0 -0.8724929 -0.4186578 0 -0.9081441 -0.4186602 0 -0.9081431 -0.3461155 0 -0.938192 -0.3461152 0 -0.938192 -0.2714391 0 -0.9624556 -0.1950913 0 -0.9807851 -0.1175382 0 -0.9930685 -0.117538 0 -0.9930685 -0.03925901 0 -0.9992291 0.03925913 0 -0.9992291 0.03925913 0 -0.9992291 0.117538 0 -0.9930685 0.1175382 0 -0.9930685 0.1950913 0 -0.9807851 0.2714391 0 -0.9624556 0.3461152 0 -0.938192 0.3461155 0 -0.938192 0.4186592 0 -0.9081435 0.418657 0 -0.9081444 0.4886281 0 -0.8724923 0.4886249 0 -0.8724941 0.5555702 0 -0.8314697 0.5555675 0 -0.8314715 0.6190955 0 -0.7853158 0.6190962 0 -0.7853152 0.6787967 0 -0.7343263 0.7343246 0 -0.6787986 0.734325 0 -0.678798 0.7853152 0 -0.6190962 0.7853159 0 -0.6190954 0.8314723 0 -0.5555664 0.8314724 0 -0.5555661 0.8724948 0 -0.4886234 0.8724955 0 -0.4886223 0.9081408 0 -0.4186649 0.9081411 0 -0.4186644 0.938193 0 -0.3461126 0.962455 0 -0.2714414 0.9624551 0 -0.2714412 0.9807861 0 -0.1950864 0.980786 0 -0.1950866 0.9930685 0 -0.1175374 0.9930685 0 -0.1175374 0.999229 0 -0.03926283 0.999229 0 0.03926283 0.9930685 0 0.1175374 0.9930685 0 0.1175374 0.980786 0 0.1950866 0.9807861 0 0.1950864 0.962455 0 0.2714414 0.9624551 0 0.2714412 0.938193 0 0.3461126 0.9081411 0 0.4186644 0.9081408 0 0.4186649 0.8724955 0 0.4886223 0.8724948 0 0.4886234 0.8314724 0 0.5555661 0.8314723 0 0.5555664 0.7853157 0 0.6190956 0.7853153 0 0.619096 0.7343252 0 0.6787979 0.7343244 0 0.6787987 0.6787967 0 0.7343263 0.6190962 0 0.7853152 0.6190955 0 0.7853158 0.5555675 0 0.8314715 0.5555702 0 0.8314697 0.4886251 0 0.8724939 0.4886279 0 0.8724923 0.418657 0 0.9081444 0.4186592 0 0.9081435 0.3461152 0 0.938192 0.3461155 0 0.938192 0.2714391 0 0.9624556 0.1950913 0 0.9807851 0.117538 0 0.9930685 0.1175382 0 0.9930685 0.03925913 0 0.9992291 0.03925913 0 0.9992291 -0.03925901 0 0.9992291 -0.117538 0 0.9930685 -0.1175382 0 0.9930685 -0.1950913 0 0.9807851 -0.2714391 0 0.9624556 -0.3461155 0 0.938192 -0.3461152 0 0.938192 -0.41866 0 0.9081432 -0.418658 0 0.908144 -0.488627 0 0.8724929 -0.4886238 0 0.8724946 -0.5555702 0 0.8314697 -0.5555675 0 0.8314715 -0.6190955 0 0.7853158 -0.6190962 0 0.7853152 -0.6787967 0 0.7343263 -0.7343244 0 0.6787987 -0.7343252 0 0.6787979 -0.7853153 0 0.619096 -0.7853157 0 0.6190956 -0.8314729 0 0.5555655 -0.8724943 0 0.4886245 -0.8724951 0 0.488623 -0.9081413 0 0.4186638 -0.9081416 0 0.4186634 -0.9381933 0 0.3461116 -0.9624547 0 0.2714425 -0.9624547 0 0.2714423 -0.9807859 0 0.1950876 -0.9807858 0 0.1950878 -0.9930684 0 0.1175386 -0.9930684 0 0.1175386 -0.999229 0 0.03926283 -0.999229 0 -0.03926283 -0.9930684 0 -0.1175386 -0.9930684 0 -0.1175386 -0.9807859 0 -0.1950877 -0.9807859 0 -0.1950877 -0.9624547 0 -0.2714423 -0.9624547 0 -0.2714425 -0.9381933 0 -0.3461116 -0.9081416 0 -0.4186634 -0.9081413 0 -0.4186638 -0.8724949 0 -0.4886233 -0.8724945 0 -0.4886242 -0.8314729 0 -0.5555655 -0.7853159 0 -0.6190954 -0.7853152 0 -0.6190962 -0.7343252 0 -0.6787979 -0.7343244 0 -0.6787987 -0.6787967 0 -0.7343263 -0.6190962 0 -0.7853152 -0.6190955 0 -0.7853158 -0.5555675 0 -0.8314715 -0.5555702 0 -0.8314697 0 1 -1.23119e-6 0 1 1.85116e-6 0 1 -9.1833e-7 0 1 6.1522e-7 0 1 -9.25756e-7 0 1 -6.15929e-7 0 1 6.16911e-7 0 1 9.22219e-7 0 1 -2.16035e-6 0 1 1.53341e-7 0 1 -1.22185e-6 0 1 9.53422e-7 0 1 1.26977e-6 0 1 -9.21549e-7 0 1 0 0 1 1.38124e-6 0 1 -6.10239e-7 0 1 0 0 1 -6.10242e-7 0 1 -1.38124e-6 0 1 0 0 1 9.21549e-7 0 1 -1.22186e-6 0 1 -1.53341e-7 0 1 2.16035e-6 0 1 -9.22219e-7 0 1 -1.26976e-6 0 1 1.27123e-6 0 1 -6.15931e-7 0 1 9.25756e-7 0 1 -1.2312e-6 0 1 2.46821e-6 0 1 9.1833e-7 0 1 -2.46822e-6 0 1 3.17487e-7 0 1 -2.45124e-6 0 1 -6.35615e-7 0 1 -3.17441e-7 0 1 2.45346e-6 0 1 6.10241e-7 0 1 0 0 1 3.17441e-7 0 1 -2.45346e-6 0 1 -6.35614e-7 0 1 1.22186e-6 0 1 6.1593e-7 0 1 -3.17487e-7 0 1 2.45124e-6 0 1 1.2312e-6 0 1 3.17562e-7 0 1 -2.46821e-6 -0.8854571 0 0.4647211 -0.9709425 0 0.2393131 -0.7485091 0 0.6631246 -0.8854567 0 0.464722 0.1205378 0 0.9927088 -0.5680672 0 0.8229823 0.3546045 0 0.9350164 0.1205359 0 0.992709 -0.3546043 0 0.9350166 -0.5680665 0 0.8229827 0.5680674 0 0.8229821 0.354603 0 0.935017 -0.1205361 0 0.9927091 -0.3546045 0 0.9350164 0.7485091 0 0.6631246 0.5680681 0 0.8229816 -0.1205373 0 0.9927089 0.8854571 0 0.4647212 0.9709425 0 0.2393131 0.8854568 0 0.4647219 0.9709424 0 0.239313 0.9709424 0 -0.239313 0.9709425 0 -0.2393131 0.8854571 0 -0.4647212 0.7485091 0 -0.6631246 0.8854568 0 -0.4647219 0.5680681 0 -0.8229816 0.5680674 0 -0.8229821 0.3546037 0 -0.9350168 0.3546038 0 -0.9350167 0.1205363 0 -0.992709 0.1205373 0 -0.9927089 -0.1205375 0 -0.9927088 -0.1205359 0 -0.992709 -0.3546051 0 -0.9350162 -0.3546037 0 -0.9350168 -0.5680665 0 -0.8229827 -0.5680672 0 -0.8229823 -0.7485091 0 -0.6631246 -0.8854571 0 -0.4647212 -0.8854568 0 -0.4647219 -0.9709425 0 -0.2393131 -0.9709424 0 -0.239313 -0.9709424 0 0.239313 0 1 -3.34806e-6 0 1 6.69621e-6 0 1 -6.69613e-6 0 1 -5.12779e-7 0 1 6.69613e-6 0 1 -1.13809e-6 0 1 -3.4142e-6 0 1 3.3482e-6 0 1 6.57356e-7 0 1 -1.06385e-6 0 1 1.87633e-7 0 1 -6.69621e-6 0 1 1.13808e-6 0 1 3.34806e-6 + + + + + + + + + + + + + + +

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

+
+
+
+
+ + + + + 0.6859207 -0.3240135 0.6515582 7.481132 0.7276763 0.3054208 -0.6141704 -6.50764 0 0.8953956 0.4452714 5.343665 0 0 0 1 + + + + -0.2908646 -0.7711008 0.5663932 4.076245 0.9551712 -0.1998834 0.2183912 1.005454 -0.05518906 0.6045247 0.7946723 5.903862 0 0 0 1 + + + + 1 0 0 0 0 1 0 0 0 0 1 0 0 0 0 1 + + + + + + + + + + 1 0 0 0 0 1 0 0 0 0 1 0 0 0 0 1 + + + + + + + + + + 1 0 0 0 0 1 0 0 0 0 1 0 0 0 0 1 + + + + + + + + + + 1 0 0 0 0 1 0 0 0 0 1 0 0 0 0 1 + + + + + + + + + + 1 0 0 0 0 1 0 0 0 0 1 0 0 0 0 1 + + + + + + + + + + 1 0 0 0 0 1 0 0 0 0 1 0 0 0 0 1 + + + + + + + + + + 1 0 0 0 0 1 0 0 0 0 1 0 0 0 0 1 + + + + + + + + + + + + + +
\ No newline at end of file diff --git a/kuka_kr5_support/meshes/kr5_arc/visual/link_2.dae b/kuka_kr5_support/meshes/kr5_arc/visual/link_2.dae new file mode 100644 index 000000000..c694f301c --- /dev/null +++ b/kuka_kr5_support/meshes/kr5_arc/visual/link_2.dae @@ -0,0 +1,571 @@ + + + + + Blender User + Blender 2.79.0 commit date:2017-09-11, commit time:10:43, hash:5bd8ac9abfa + + 2017-11-10T20:04:10 + 2017-11-10T20:04:10 + + Z_UP + + + + + + + 49.13434 + 1.777778 + 0.1 + 100 + + + + + + 0 + 0 + 0 + + + + + + + + + 1 1 1 + 1 + 0 + 0.00111109 + + + + + 0 + 0 + 8192 + 1 + 1 + 1 + 1 + 0 + 0 + 0 + 1 + 29.99998 + 75 + 0.15 + 1 + 0 + 1 + 2 + 1.000799 + 30.002 + 1 + 3 + 0.04999995 + 2880 + 3 + 1 + 0 + 0 + 2 + 1 + 1 + 1 + 0 + 1 + 0.1 + 0.1 + 1 + 0.000999987 + 1 + 0 + 0 + 1 + 1 + 1 + 1 + 1 + 1 + 1 + 2 + 1 + 1 + 1 + 1 + 0 + + + + + + + + + + + + 0 0 0 1 + + + 0 0 0 1 + + + 0.09803922 0.09803922 0.09803922 1 + + + 0.5 0.5 0.5 1 + + + 0 + + + 1 1 1 1 + + + 1 + + + + + + + + + + + 0 0 0 1 + + + 0 0 0 1 + + + 1 1 1 1 + + + 0.5 0.5 0.5 1 + + + 0 + + + 1 1 1 1 + + + 1 + + + + + + + + + + + 0 0 0 1 + + + 0 0 0 1 + + + 1 0.4980392 0 1 + + + 0.5 0.5 0.5 1 + + + 0 + + + 1 1 1 1 + + + 1 + + + + + + + + + + + 0 0 0 1 + + + 0 0 0 1 + + + 0.09803922 0.09803922 0.09803922 1 + + + 0.5 0.5 0.5 1 + + + 0 + + + 1 1 1 1 + + + 1 + + + + + + + + + + + 0 0 0 1 + + + 0 0 0 1 + + + 0.4 0.4 0.4 1 + + + 0.5 0.5 0.5 1 + + + 0 + + + 1 1 1 1 + + + 1 + + + + + + + + + + + 0 0 0 1 + + + 0 0 0 1 + + + 0 0 0 1 + + + 0.5 0.5 0.5 1 + + + 0 + + + 1 1 1 1 + + + 1 + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + 0.57 -0.04415261 0.162 0.57 -0.03599995 0.162 0.57 -0.03599995 -0.01899999 0.57 -0.04415261 -0.01899999 0.564 -0.02999997 0.162 0.564 -0.02999997 -0.01899999 0.5558474 -0.02999997 -0.01899999 0.5558474 -0.02999997 0.162 0.5558474 0.02999997 0.162 0.564 0.02999997 0.162 0.564 0.02999997 -0.01899999 0.5558474 0.02999997 -0.01899999 0.57 0.03599995 0.162 0.57 0.03599995 -0.01899999 0.57 0.04415261 -0.01899999 0.57 0.04415261 0.162 0.636 0.02999997 0.162 0.636 0.02999997 -0.01899999 0.63 0.03599995 -0.01899999 0.63 0.03599995 0.162 0.63 0.04415261 0.162 0.63 0.04415261 -0.01899999 0.6441526 0.02999997 -0.01899999 0.6441526 0.02999997 0.162 0.63 -0.03599995 0.162 0.63 -0.04415261 -0.01899999 0.63 -0.03599995 -0.01899999 0.63 -0.04415261 0.162 0.636 -0.02999997 -0.01899999 0.636 -0.02999997 0.162 0.6441526 -0.02999997 0.162 0.6441526 -0.02999997 -0.01899999 0.626 -0.04815262 -0.01899999 0.626 -0.04815262 0.162 0.574 -0.04815262 -0.01899999 0.574 -0.04815262 0.162 0.5518474 -0.02599996 -0.01899999 0.5518474 -0.02599996 0.162 0.5628474 -0.04815262 -0.01899999 0.5518474 -0.03715264 -0.01899999 0.5518474 -0.03715264 -0.03099995 0.5628474 -0.04815262 -0.03099995 0.5518474 0.02599996 -0.01899999 0.5518474 0.02599996 0.162 0.574 0.04815262 -0.01899999 0.574 0.04815262 0.162 0.5518474 0.03715264 -0.01899999 0.5628474 0.04815262 -0.01899999 0.5518474 0.03715264 -0.03099995 0.5628474 0.04815262 -0.03099995 0.626 0.04815262 -0.01899999 0.626 0.04815262 0.162 0.6481526 -0.02599996 0.162 0.6481526 0.02599996 0.162 0.6481526 0.02599996 -0.01899999 0.6481526 0.03715264 -0.01899999 0.6371526 0.04815262 -0.01899999 0.6371526 0.04815262 -0.03099995 0.6481526 0.03715264 -0.03099995 0.6371526 -0.04815262 -0.03099995 0.6481526 -0.03715264 -0.03099995 0.6371526 -0.04815262 -0.01899999 0.6481526 -0.03715264 -0.01899999 0.6481526 -0.02599996 -0.01899999 + + + + + + + + + + -1 0 0 -0.707103 -0.7071106 0 -0.7071127 -0.7071009 0 0 -1 0 0 1 0 -0.7071127 0.7071009 0 -0.707103 0.7071107 0 0.7071127 0.7071009 0 0.707103 0.7071107 0 1 0 0 0.707103 -0.7071106 0 0.7071127 -0.7071009 0 0.7070983 -0.7071154 0 0.7071128 -0.7071008 0 -0.7070983 -0.7071154 0 -0.7071128 -0.7071008 0 -0.7070981 -0.7071155 0 -0.7071126 -0.707101 0 0 0 1 -0.7071043 -0.7071093 0 -0.707109 -0.7071046 0 -0.7071127 0.707101 0 -0.7070981 0.7071155 0 -0.7071129 0.7071008 0 -0.7070983 0.7071154 0 3.26198e-7 0 1 0 0 1 -0.7071043 0.7071093 0 -0.707109 0.7071046 0 0.7071129 0.7071008 0 0.7070983 0.7071154 0 3.56985e-6 0 1 -1.47376e-6 0 1 -3.56985e-6 0 1 -5.29161e-7 0 1 2.35183e-6 0 1 -2.35183e-6 0 1 4.70365e-7 0 1 1.47376e-6 0 1 0.7071127 0.707101 0 0.7070981 0.7071155 0 -3.26198e-7 0 1 0 0 1 0.7071068 0.7071068 0 0.707109 0.7071046 0 0.7071068 -0.7071068 0 0.707109 -0.7071046 0 0.7070981 -0.7071155 0 0.7071126 -0.707101 0 0 -1 1.86563e-7 0 1 1.86563e-7 0 0 -1 + + + + + + + + + + + + + + +

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

+
+
+
+ + + + 0.1416358 0.05949503 -0.1213582 0.1391479 0.05843895 -0.1197061 0.1313883 0.07671982 -0.1197061 0.1338761 0.07777589 -0.1213582 0.1542528 0.06485056 -0.1096256 0.1512378 0.06357079 -0.1042939 0.1487499 0.06251472 -0.1026418 0.153134 0.06437563 -0.1067003 0.1430072 0.06007713 -0.1021577 0.1459138 0.06131088 -0.1019057 0.1538072 0.06466144 -0.1158642 0.1544848 0.06494903 -0.1127832 0.1522864 0.06401586 -0.1185669 0.1380994 0.05799382 -0.1054331 0.1403146 0.05893415 -0.1033732 0.1473786 0.06193262 -0.1218423 0.1500713 0.0630756 -0.1206268 0.144472 0.06069886 -0.1220943 0.136133 0.05715918 -0.1143743 0.1365786 0.05734831 -0.1081358 0.135901 0.05706071 -0.1112168 0.1372519 0.05763411 -0.1172997 0.1294921 0.07591497 -0.1172997 0.1467249 0.08322989 -0.1127832 0.1445267 0.08229678 -0.1185669 0.1423115 0.08135646 -0.1206268 0.1396188 0.08021348 -0.1218423 0.1460475 0.0829423 -0.1158642 0.1367121 0.07897973 -0.1220943 0.143478 0.08185166 -0.1042939 0.1453742 0.0826565 -0.1067003 0.146493 0.08313143 -0.1096256 0.1409901 0.08079558 -0.1026418 0.1283733 0.07544004 -0.1143743 0.1281413 0.07534158 -0.1112168 0.1352475 0.07835799 -0.1021577 0.1381541 0.07959175 -0.1019057 0.1303396 0.07627475 -0.1054331 0.1288188 0.07562917 -0.1081358 0.1325548 0.07721501 -0.1033732 0.1668448 -0.01928347 -0.1158661 0.1651921 -0.01928347 -0.1185685 0.1668448 5.7609e-4 -0.1158661 0.1651921 5.7609e-4 -0.1185685 0.1481299 5.7609e-4 -0.1081339 0.1497825 5.7609e-4 -0.1054314 0.1521894 5.7609e-4 -0.103372 0.1473931 5.7609e-4 -0.1112146 0.1582726 5.7609e-4 -0.1019058 0.1551149 5.7609e-4 -0.1021572 0.1613534 5.7609e-4 -0.1026425 0.1488594 5.7609e-4 -0.1172979 0.1476445 5.7609e-4 -0.1143724 0.1661152 5.7609e-4 -0.1067021 0.1640558 5.7609e-4 -0.1042952 0.1536211 5.7609e-4 -0.1213575 0.1509188 5.7609e-4 -0.1197048 0.1675814 5.7609e-4 -0.1127853 0.1673301 5.7609e-4 -0.1096276 0.1627852 5.7609e-4 -0.1206279 0.156702 5.7609e-4 -0.1220942 0.1598597 5.7609e-4 -0.1218428 0.1675814 -0.01928347 -0.1127853 0.1627852 -0.01928347 -0.1206279 0.1598597 -0.01928347 -0.1218428 0.156702 -0.01928347 -0.1220942 0.1536211 -0.01928347 -0.1213575 0.1673301 -0.01928347 -0.1096276 0.1661152 -0.01928347 -0.1067021 0.1509188 -0.01928347 -0.1197048 0.1488594 -0.01928347 -0.1172979 0.1640558 -0.01928347 -0.1042952 0.1613534 -0.01928347 -0.1026425 0.1476445 -0.01928347 -0.1143724 0.1473931 -0.01928347 -0.1112146 0.1582726 -0.01928347 -0.1019058 0.1521894 -0.01928347 -0.103372 0.1551149 -0.01928347 -0.1021572 0.1481299 -0.01928347 -0.1081339 0.1497825 -0.01928347 -0.1054314 0.512248 0.05172783 -0.1173465 0.5058049 0.03301554 -0.1173465 0.5047851 0.03336668 -0.1194633 0.5112282 0.05207896 -0.1194633 0.5058049 0.03301554 -0.1126535 0.5047851 0.03336668 -0.1105367 0.5031967 0.03391361 -0.1088567 0.4989765 0.03536671 -0.1074064 0.5011952 0.03460276 -0.1077782 0.5061563 0.03289455 -0.115 0.4947563 0.03681987 -0.1088567 0.4967578 0.03613066 -0.1077782 0.5011952 0.03460276 -0.1222218 0.5031967 0.03391361 -0.1211433 0.4917967 0.03783893 -0.115 0.4931679 0.0373668 -0.1105367 0.4921481 0.03771793 -0.1126535 0.4967578 0.03613066 -0.1222218 0.4989765 0.03536671 -0.1225935 0.4931679 0.0373668 -0.1194633 0.4921481 0.03771793 -0.1173465 0.4947563 0.03681987 -0.1211433 0.5125995 0.05160683 -0.115 0.5076384 0.0533151 -0.1222218 0.5096399 0.05262589 -0.1211433 0.512248 0.05172783 -0.1126535 0.503201 0.054843 -0.1222218 0.5054197 0.05407905 -0.1225935 0.5112282 0.05207896 -0.1105367 0.4996111 0.05607908 -0.1194633 0.5011995 0.05553215 -0.1211433 0.4982399 0.05655121 -0.115 0.4985913 0.05643022 -0.1173465 0.503201 0.054843 -0.1077782 0.5054197 0.05407905 -0.1074064 0.5076384 0.0533151 -0.1077782 0.5096399 0.05262589 -0.1088567 0.4996111 0.05607908 -0.1105367 0.4985913 0.05643022 -0.1126535 0.5011995 0.05553215 -0.1088567 0.488974 -0.02415496 -0.118776 0.49309 -0.04351925 -0.118776 0.492264 -0.04369479 -0.1165554 0.488148 -0.02433049 -0.1165554 0.4886422 -0.02422547 -0.1118896 0.489914 -0.02395516 -0.1099012 0.4917246 -0.02357029 -0.1084119 0.4880337 -0.02435481 -0.1141825 0.4984605 -0.02213853 -0.1080728 0.4938967 -0.0231086 -0.1075675 0.4962177 -0.02261525 -0.1074506 0.4904307 -0.02384531 -0.120627 0.5018622 -0.02141547 -0.111224 0.5004055 -0.02172511 -0.109373 0.4923756 -0.02343189 -0.1219272 0.4946184 -0.02295517 -0.1225494 0.5028025 -0.02121561 -0.1158175 0.5026881 -0.02123993 -0.1134446 0.4991116 -0.02200013 -0.1215881 0.4969395 -0.02246183 -0.1224325 0.5009221 -0.02161526 -0.1200988 0.5021939 -0.02134495 -0.1181104 0.4921497 -0.04371911 -0.1141825 0.4945467 -0.04320961 -0.120627 0.4987344 -0.04231947 -0.1225494 0.4964917 -0.04279619 -0.1219272 0.4927582 -0.04358977 -0.1118896 0.5032276 -0.04136443 -0.1215881 0.5010555 -0.04182612 -0.1224325 0.4958406 -0.04293459 -0.1084119 0.49403 -0.0433194 -0.1099012 0.5069185 -0.04057991 -0.1158175 0.5050381 -0.04097956 -0.1200988 0.5063099 -0.04070925 -0.1181104 0.5025765 -0.04150283 -0.1080728 0.5003337 -0.04197955 -0.1074506 0.4980127 -0.04247289 -0.1075675 0.5059782 -0.04077976 -0.111224 0.5068042 -0.04060417 -0.1134446 0.5045215 -0.04108941 -0.109373 + + + + + + + + + + -0.4800879 -0.2037827 -0.8532223 -0.4800964 -0.2037906 -0.8532156 0.3907287 -0.9205059 -3.23413e-6 0.390699 -0.9205185 -2.81544e-5 0.3907417 -0.9205004 -5.63164e-5 0.3907267 -0.9205068 -5.86639e-7 0.3907296 -0.9205055 -3.63848e-6 0.3907651 -0.9204905 -4.69365e-5 0.3907309 -0.9205051 2.38822e-6 0.3907277 -0.9205064 2.5291e-6 0.3907313 -0.9205049 -7.01881e-7 0.3907145 -0.920512 2.81582e-5 0.3907326 -0.9205043 2.10565e-6 0.3907358 -0.9205029 -1.29368e-5 0.3908039 -0.920474 -7.04071e-6 0.3907433 -0.9204998 -1.61715e-6 0.3907259 -0.9205071 -1.1941e-6 0.3907797 -0.9204843 4.22378e-5 0.3907229 -0.9205085 -1.87726e-5 0.390722 -0.9205088 -5.05818e-6 -0.6992965 -0.2968319 -0.6502886 -0.6992862 -0.2968286 -0.6503012 -0.3907122 0.9205129 -1.61705e-5 -0.3907321 0.9205046 -1.70034e-6 -0.390722 0.9205088 -1.8771e-5 -0.3907325 0.9205043 8.73335e-6 -0.3907241 0.9205079 4.69304e-5 -0.3907332 0.920504 1.45829e-6 -0.3907011 0.9205178 9.3848e-6 -0.3907299 0.9205054 2.82999e-6 -0.3907331 0.9205042 0 -0.3907358 0.920503 3.67516e-6 -0.3907245 0.9205077 1.87702e-5 -0.3907305 0.9205051 -3.23434e-6 -0.3907293 0.9205057 -2.34793e-6 -0.3907485 0.9204976 -1.87724e-5 -0.390688 0.9205233 -1.87701e-5 -0.3907234 0.9205082 0 -0.3907284 0.9205061 5.0582e-6 -0.3907284 0.9205061 -3.8642e-6 -0.2138962 -0.09079664 -0.9726276 -0.2139021 -0.090797 -0.9726262 -0.8500444 -0.3608198 -0.3837102 -0.8500509 -0.360826 -0.3836901 -0.9175872 -0.3894906 -0.07956713 -0.9175881 -0.3894943 -0.07953882 -0.8953104 -0.3800404 0.2323548 -0.8953126 -0.3800382 0.2323498 -0.7853856 -0.3333792 0.5215628 -0.7853885 -0.3333763 0.5215603 -0.5985894 -0.2540857 0.7596915 -0.5985804 -0.2540861 0.7596986 -0.3532233 -0.1499312 0.9234468 -0.3532082 -0.1499305 0.9234527 -0.07322412 -0.03108263 0.9968311 -0.07322853 -0.03108304 0.9968307 0.2139103 0.09079718 0.9726245 0.2138974 0.09079605 0.9726274 0.4800833 0.2037847 0.8532245 0.4800995 0.2037873 0.8532147 0.6992844 0.2968297 0.6503025 0.6992848 0.2968305 0.6503018 0.8500518 0.3608266 0.3836876 0.8500522 0.3608269 0.3836864 0.9175856 0.3894945 0.07956701 0.917587 0.389492 0.07956278 0.8953133 0.3800361 -0.2323501 0.8953067 0.3800339 -0.2323797 0.7853878 0.3333746 -0.5215624 0.7853883 0.3333747 -0.5215617 0.5985968 0.2540901 -0.7596843 0.5985888 0.2540816 -0.7596934 0.3532103 0.1499301 -0.923452 0.3532126 0.1499295 -0.9234512 0.07323008 0.03108441 -0.9968306 0.0732274 0.03108435 -0.9968307 0.8531073 0 -0.5217356 0.8531093 0 -0.5217324 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0.9725798 0 -0.2325698 0.9725801 0 -0.2325681 0 -1 -2.34654e-6 0 -1 2.02137e-7 0 -1 0 0 -1 4.6929e-6 0 -1 -2.3464e-6 0 -1 0 0 -1 -1.61709e-6 0 -1 -2.34649e-6 0 -1 4.25679e-7 0.6501235 0 -0.7598286 0.6501277 0 -0.759825 0.9968459 0 0.07936251 0.9968458 0 0.0793631 0.9235301 0 0.383526 0.9235312 0 0.3835234 0.7598239 0 0.650129 0.759827 0 0.6501253 0.5217353 0 0.8531075 0.2325699 0 0.9725797 0.2325698 0 0.9725797 -0.07936578 0 0.9968456 -0.07936578 0 0.9968456 -0.3835217 0 0.923532 -0.6501254 0 0.759827 -0.8531219 0 0.5217117 -0.8531239 0 0.5217084 -0.9725734 0 0.2325965 -0.9725738 0 0.2325948 -0.9968458 0 -0.0793631 -0.9968458 0 -0.0793631 -0.9235317 0 -0.3835219 -0.9235329 0 -0.3835194 -0.7598239 0 -0.650129 -0.759827 0 -0.6501253 -0.5217353 0 -0.8531075 -0.2325699 0 -0.9725797 -0.2325698 0 -0.9725797 0.07936543 0 -0.9968457 0.3835217 0 -0.923532 0.8424699 -0.2900773 -0.4539821 0.8424715 -0.2900759 -0.4539799 -0.3255498 -0.9455249 1.66865e-5 -0.3255648 -0.9455198 -1.66888e-5 -0.3255078 -0.9455394 0 -0.3255618 -0.9455208 0 -0.3255568 -0.9455225 8.34397e-6 -0.325549 -0.9455252 -8.62412e-6 -0.325559 -0.9455218 -8.34146e-6 -0.3255724 -0.9455171 5.30722e-7 -0.3255722 -0.9455172 0 -0.3255547 -0.9455232 -2.87491e-6 -0.3255646 -0.9455198 -1.29624e-6 -0.3255739 -0.9455167 2.54402e-6 -0.3255673 -0.945519 0 -0.3255624 -0.9455206 2.50266e-5 -0.3255703 -0.9455178 0 -0.3255723 -0.9455173 -2.24815e-6 -0.3255628 -0.9455205 1.71743e-6 -0.3255459 -0.9455263 -1.66818e-5 0.9338757 -0.3215616 -0.1564432 0.9338701 -0.3215539 -0.1564922 0.3256056 0.9455057 5.75041e-6 0.325518 0.945536 5.00425e-5 0.3254517 0.9455587 0 0.3255572 0.9455224 -2.50262e-5 0.3255718 0.9455174 -7.56772e-7 0.3255631 0.9455204 0 0.325559 0.9455218 0 0.3255683 0.9455186 -8.99261e-6 0.3255722 0.9455172 0 0.3255718 0.9455174 2.2299e-6 0.3255607 0.9455212 0 0.3255721 0.9455173 2.5026e-5 0.3255637 0.9455202 0 0.3255639 0.9455201 -3.32483e-5 0.3255722 0.9455172 -2.0858e-6 0.3255686 0.9455184 2.12289e-6 0.3255689 0.9455183 0 0.325531 0.9455314 0 0.6685938 -0.2302196 -0.7070935 0.668622 -0.2302195 -0.707067 0.4292249 -0.1477977 -0.8910229 0.4292291 -0.1477948 -0.8910214 0.1479352 -0.05093741 -0.9876845 0.1479323 -0.05093556 -0.987685 -0.1479335 0.05093598 -0.9876848 -0.147926 0.05093747 -0.9876859 -0.4292386 0.1477985 -0.8910163 -0.4292215 0.1477956 -0.8910249 -0.6685968 0.2302147 -0.7070924 -0.6685984 0.2302222 -0.7070884 -0.8424638 0.2900797 -0.4539918 -0.8424615 0.2900857 -0.4539922 -0.9338757 0.3215657 -0.156435 -0.9338783 0.3215585 -0.1564334 -0.9338779 0.3215597 0.1564339 -0.9338757 0.3215657 0.156435 -0.8424652 0.2900785 0.45399 -0.842461 0.2900856 0.4539932 -0.6686009 0.2302157 0.7070881 -0.6685984 0.2302222 0.7070884 -0.4292315 0.1477991 0.8910196 -0.4292221 0.1477957 0.8910247 -0.1479217 0.0509361 0.9876866 -0.1479358 0.05093741 0.9876844 0.1479328 -0.05093741 0.9876848 0.1479226 -0.05093568 0.9876864 0.429232 -0.1477972 0.8910197 0.4292287 -0.1477946 0.8910216 0.6685926 -0.23022 0.7070946 0.668622 -0.2302195 0.707067 0.8424714 -0.290076 0.4539801 0.8424685 -0.2900782 0.4539842 0.9338671 -0.3215628 0.1564917 0.9338774 -0.3215559 0.1564453 -0.9142711 -0.1943339 -0.3554472 -0.9142718 -0.1943333 -0.3554455 -0.2078915 0.9781519 -4.17101e-6 -0.2078884 0.9781526 -8.62345e-6 -0.207924 0.978145 -3.75382e-5 -0.2079091 0.9781482 0 -0.2079141 0.9781471 3.78381e-7 -0.2078674 0.978157 5.21343e-6 -0.2079384 0.9781419 -3.59408e-6 -0.2079146 0.978147 8.34312e-6 -0.207929 0.978144 -4.53449e-6 -0.2079105 0.9781479 5.82249e-6 -0.2079222 0.9781454 -1.04296e-5 -0.2079111 0.9781478 -7.96074e-7 -0.2079173 0.9781465 1.12412e-6 -0.2079101 0.9781481 -2.92014e-5 -0.2079128 0.9781474 0 -0.2079057 0.9781489 3.24052e-6 -0.2079153 0.9781469 -3.12888e-6 -0.2079099 0.978148 1.43737e-5 -0.976965 -0.2076548 -0.04918324 -0.9769634 -0.2076626 -0.04918181 0.2079162 -0.9781467 1.66874e-5 0.2079313 -0.9781434 1.66896e-5 0.2079499 -0.9781395 -3.65083e-6 0.2079027 -0.9781496 2.50294e-5 0.2079104 -0.9781479 -4.49611e-6 0.2078971 -0.9781507 2.08564e-5 0.2079105 -0.9781479 -2.24808e-6 0.2079446 -0.9781407 -1.1501e-5 0.207917 -0.9781465 -8.34254e-6 0.207911 -0.9781478 -1.85605e-6 0.2079089 -0.9781483 2.12281e-6 0.2079215 -0.9781456 -8.34172e-6 0.2079151 -0.978147 2.87487e-6 0.2079117 -0.9781476 -2.65353e-6 0.2079104 -0.9781479 2.92732e-6 0.2079796 -0.9781333 -5.21544e-7 0.2078983 -0.9781505 -2.24808e-6 0.207905 -0.9781491 0 -0.7621038 -0.1619898 -0.626863 -0.7621005 -0.1619929 -0.6268663 -0.5353136 -0.1137853 -0.8369542 -0.5353176 -0.1137897 -0.8369511 -0.2561709 -0.05445235 -0.9650967 -0.2561688 -0.05444973 -0.9650973 0.04813152 0.01023012 -0.9987887 0.04812592 0.01022988 -0.9987889 0.3476523 0.07389461 -0.9347072 0.3476603 0.07389909 -0.9347039 0.6131843 0.1303395 -0.7791128 0.6131947 0.1303384 -0.7791047 0.8186498 0.1740099 -0.5472961 0.8186506 0.17401 -0.5472949 0.9440122 0.2006602 -0.2618712 0.944014 0.2006537 -0.2618698 0.9769651 0.2076573 0.04916954 0.9769606 0.2076669 0.04921877 0.9142709 0.1943302 0.35545 0.9142841 0.194348 0.3554061 0.7620964 0.1619912 0.6268716 0.7620996 0.1619856 0.6268692 0.5353008 0.1137824 0.8369628 0.5353091 0.1137858 0.836957 0.2561671 0.05445039 0.9650978 0.2561758 0.05445033 0.9650955 -0.04812568 -0.01023042 0.998789 -0.04812824 -0.01023036 0.9987888 -0.3476629 -0.07389903 0.9347029 -0.3476692 -0.0738964 0.9347007 -0.6131644 -0.1303319 0.7791298 -0.6131587 -0.1303324 0.7791342 -0.818661 -0.1740167 0.5472772 -0.818659 -0.1740097 0.5472827 -0.9440194 -0.2006565 0.2618483 -0.944021 -0.2006622 0.261838 + + + + + + + + + + + + + + +

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

+
+
+
+ + + + 0.3100656 -0.03701871 -0.239 0.3110638 -0.03680503 -0.239 0.3309987 -0.05867552 -0.239 0.3120507 -0.03621619 -0.239 0.331 -0.03636586 -0.239 0.3071542 -0.03299051 -0.239 0.289 -0.03636586 -0.239 0.359355 -0.01703715 -0.2390159 0.3563659 -0.02004116 -0.2390015 0.307 -0.03399997 -0.239 0.3072007 -0.03513199 -0.239 0.3080025 -0.036255 -0.239 0.308539 -0.03135752 -0.239 0.286 -0.0333659 -0.239 0.3563659 -0.03036594 -0.239 0.3077545 -0.03201061 -0.239 0.3533659 -0.0333659 -0.239 0.334 -0.0333659 -0.239 0.3119525 -0.03169679 -0.239 0.2636341 -0.03036588 -0.239 0.2666341 -0.0333659 -0.239 0.3127992 -0.0328679 -0.239 0.2636341 -0.01701635 -0.2390005 0.3110638 -0.03119492 -0.239 0.289 -0.0603165 -0.239 0.3089362 -0.03680503 -0.239 0.3099344 -0.03098118 -0.239 0.313 -0.03399997 -0.239 0.3128166 -0.03506851 -0.239 0.274191 -0.0333659 -0.2488127 0.2666341 -0.0333659 -0.2483434 0.286 -0.0333659 -0.2489735 0.2636341 -0.03036588 -0.2481571 0.2636341 -0.01687556 -0.2421371 0.2636339 -0.01518702 -0.2481459 0.2636341 -0.01638042 -0.2447327 0.1864995 -0.0170381 -0.2394101 0.4140282 -0.01704025 -0.2395968 0.4274788 -0.01687556 -0.2368628 0.1733862 -0.01687556 -0.2368628 0.3563659 -0.01985782 -0.2425138 0.3563659 -0.03036588 -0.2467589 0.3563655 -0.01892429 -0.2467508 0.3533659 -0.0333659 -0.2470366 0.334 -0.0333659 -0.2483935 0.3430334 -0.0333659 -0.2479926 0.331 -0.03636586 -0.2485268 0.331 -0.05836927 -0.2485268 0.3561394 -0.06066316 -0.16 0.3155603 -0.06195551 -0.16 0.289 -0.05996489 -0.2490144 0.2702168 -0.06388741 -0.16 0.289 -0.03636586 -0.2490144 0.3082958 -0.03646892 -0.229 0.3092791 -0.03692495 -0.229 0.3129906 -0.03363704 -0.229 0.3106587 -0.03694671 -0.229 0.3126564 -0.03260582 -0.229 0.3120507 -0.03178375 -0.229 0.3119525 -0.03630316 -0.229 0.3128309 -0.03507393 -0.229 0.3110638 -0.03119492 -0.229 0.3100656 -0.03098118 -0.229 0.3089362 -0.03119492 -0.229 0.3080474 -0.03169679 -0.229 0.3072007 -0.03286796 -0.229 0.3069953 -0.03429853 -0.229 0.3074782 -0.03566062 -0.229 0.2741371 -0.06061357 -0.2488103 0.2488495 -0.06188845 -0.2472386 0.2488611 -0.01556611 -0.2472397 0.2219188 -0.01642066 -0.2445467 0.205287 -0.01687556 -0.2421371 0.3965647 -0.01687556 -0.2421371 0.3593659 -0.01687556 -0.2421371 0.4526265 -0.0155639 -0.2317541 0.4638559 -0.01448971 -0.229465 0.4636743 -0.05615741 -0.2295098 0.4352591 -0.05595582 -0.2352822 0.4402557 -0.01638042 -0.2342672 0.413888 -0.05636525 -0.2396237 0.1600423 -0.01638042 -0.2342672 0.1862565 -0.06569784 -0.2393696 0.1418737 -0.0690537 -0.230731 0.1432956 -0.0152648 -0.2310399 0.22175 -0.06339854 -0.2445278 0.3593659 -0.01638042 -0.2447327 0.3593659 -0.01581227 -0.2464814 0.3793393 -0.01640176 -0.2446341 0.3794006 -0.05709594 -0.2446275 0.3430973 -0.05799311 -0.2479882 0.3560564 -0.06084007 -0.16 0.4352959 -0.05875933 -0.16 0.4352936 -0.05858474 -0.16 0.32462 0.06850284 -0.16 0.3527038 0.0678482 -0.16 -0.06084483 -0.05726844 -0.16 -0.06071633 -0.05714911 -0.16 -0.05023628 -0.06674391 -0.16 -0.05013048 -0.06660425 -0.16 -0.07018047 -0.04511797 -0.16 -0.07003211 -0.04502445 -0.16 0.3754575 0.06713682 -0.16 -0.04013878 -0.07318049 -0.16 0.5090093 -0.05875933 -0.16 -0.04005539 -0.07302659 -0.16 0.5090123 -0.05858474 -0.16 -0.0781241 -0.02944773 -0.16 -0.0779609 -0.02938354 -0.16 -0.02844274 -0.07848203 -0.16 0.5343785 -0.0596503 -0.16 -0.02838009 -0.07831871 -0.16 -0.02146571 -0.08069348 -0.16 0.5343903 -0.05947601 -0.16 -0.02142035 -0.08052468 -0.16 -0.08176767 -0.01679652 -0.16 0.5666136 -0.06295847 -0.16 0.5672185 -0.06286966 -0.16 -0.08159631 -0.01676064 -0.16 0.4706274 0.06538432 -0.16 -0.01395165 -0.08224159 -0.1599976 0.4695931 0.06520533 -0.16 -0.006099879 -0.08329528 -0.16 -0.006086826 -0.083121 -0.16 -0.08334356 -0.004980564 -0.16 -0.08316892 -0.004968941 -0.16 0.5928713 -0.06714516 -0.16 0.5928922 -0.06697165 -0.16 0.003736913 -0.08350592 -0.16 0.003639519 -0.08333301 -0.16 0.6 -0.0677163 -0.16 0.6 -0.06754112 -0.16 0.6091791 -0.06698083 -0.16 -0.08328533 0.006919682 -0.1599973 0.01145762 -0.08310365 -0.16 0.6091539 -0.06680768 -0.16 0.01144498 -0.08292949 -0.16 -0.08141863 0.01941978 -0.16 -0.08124828 0.0193789 -0.16 0.6165153 -0.06542152 -0.16 0.61647 -0.0652526 -0.16 -0.07706201 0.03227913 -0.1599973 0.6267866 -0.06208413 -0.16 0.6267181 -0.06192278 -0.16 -0.07138103 0.04353916 -0.16 -0.07123243 0.04344624 -0.16 0.6353513 -0.05753022 -0.16 0.6352612 -0.05738037 -0.16 -0.06150531 0.05664414 -0.16 -0.06137627 0.05652523 -0.16 0.09240102 -0.0755791 -0.16 0.09238606 -0.07540518 -0.16 0.6394741 -0.05453878 -0.16 0.6395793 -0.05467838 -0.16 -0.04950362 0.06733012 -0.16 0.5219366 0.06492173 -0.16 -0.04940003 0.06718862 -0.16 0.5219372 0.06474715 -0.16 -0.03589904 0.07521402 -0.16 -0.03597527 0.0753718 -0.16 0.6468574 -0.04832923 -0.16 0.6469797 -0.04845458 -0.16 0.5479637 0.06512439 -0.16 -0.0231527 0.08006274 -0.16 -0.02320218 0.08023071 -0.16 0.5479597 0.06529897 -0.16 0.1355522 -0.07216632 -0.16 0.1355391 -0.07199221 -0.16 0.6538907 -0.04037892 -0.16 0.6540301 -0.0404849 -0.16 -0.01150333 0.08252984 -0.16 -0.01152944 0.08270281 -0.16 0.6589319 -0.03293687 -0.16 0.6587796 -0.03285068 -0.16 0.5759363 0.06609654 -0.16 -0.002284288 0.08333092 -0.16 -0.003618717 0.08342313 -0.16 0.5745613 0.06619828 -0.16 0.6620881 -0.02646553 -0.16 0.002288699 0.08348315 -0.16 0.6619272 -0.02639722 -0.16 0.006359875 0.08308279 -0.16 0.6645203 -0.01927274 -0.16 0.6646875 -0.01932388 -0.16 0.1814119 -0.06894105 -0.16 0.1793437 -0.06889659 -0.16 0.6658493 -0.01442331 -0.1599973 0.0343697 0.08157253 -0.16 0.03429526 0.08140248 -0.16 0.6669556 -0.007551968 -0.16 0.6671292 -0.007572472 -0.16 0.5977846 0.06730026 -0.16 0.5976649 0.06747186 -0.16 0.6674007 6.60023e-4 -0.16 0.6675258 -0.00167495 -0.16 0.6035178 0.06726408 -0.16 0.6030084 0.06746381 -0.16 0.6674904 0.002652764 -0.16 0.08556884 0.0785008 -0.16 0.08233517 0.07885479 -0.16 0.6666399 0.009849369 -0.16 0.6667667 0.01026707 -0.16 0.6097845 0.06662029 -0.16 0.6092903 0.0668714 -0.16 0.6133067 0.06610596 -0.1599973 0.229808 -0.06608319 -0.16 0.2279217 -0.06600469 -0.16 0.6647829 0.01853644 -0.16 0.6653871 0.01684629 -0.16 0.6184022 0.06487041 -0.1599973 0.6640186 0.02144473 -0.16 0.6255887 0.06250077 -0.16 0.6265898 0.06190276 -0.16 0.6622414 0.02572244 -0.16 0.6624027 0.02578961 -0.16 0.6596584 0.03144407 -0.1599973 0.6332881 0.05874782 -0.16 0.633966 0.05816191 -0.16 0.1321909 0.07627862 -0.16 0.6572738 0.03540593 -0.16 0.6574224 0.03549796 -0.16 0.6387919 0.05506551 -0.16 0.6388946 0.05520695 -0.16 0.6541365 0.04006516 -0.16 0.1479842 0.07533252 -0.16 0.654277 0.04016906 -0.16 0.6500777 0.04516994 -0.1599973 0.2704206 -0.0640515 -0.16 0.6465467 0.04878574 -0.16 0.6466661 0.04891377 -0.16 0.2017488 0.07308423 -0.16 0.3155668 -0.06212997 -0.16 0.2365417 0.07149094 -0.16 0.2654996 0.07062619 -0.16 0.1362692 -0.0144388 -0.2293632 0.5025185 -0.002502143 -0.2194883 0.5048798 -1.2658e-5 -0.2188481 0.505012 -0.05649495 -0.218829 0.4965056 -0.006148576 -0.2210396 0.4877935 -0.009412348 -0.2232872 0.4807822 -0.01133859 -0.2250961 0.4728904 -0.01302289 -0.2271321 0.1227744 -0.01223194 -0.2260722 0.09296268 -0.07329767 -0.2188016 0.1113544 -0.009412348 -0.2232872 0.1049855 -0.007274568 -0.2217341 0.09711885 -0.003540456 -0.2198156 0.09307003 6.4239e-5 -0.21883 -0.07560235 -0.03086888 -0.113991 -0.07661992 -0.02885603 -0.1139202 -0.06956815 -0.04280483 -0.1144109 -0.06882911 -0.04426664 -0.1144623 -0.08007055 -0.0167182 -0.1136801 -0.07753992 -0.02579522 -0.1138562 -0.08129507 -0.008332431 -0.1135949 -0.08172202 -0.004872918 -0.1135652 -0.08173263 2.12356e-5 -0.1135644 -0.08172202 0.006800055 -0.1135652 -0.07984089 0.01904124 -0.113696 -0.07580059 0.03134328 -0.1139772 -0.07002514 0.04269129 -0.1143791 -0.06154376 0.05388116 -0.1149693 -0.06034541 0.05557531 -0.1150527 -0.06658649 0.04738754 -0.1146184 -0.05215674 0.06289291 -0.1156225 -0.04858916 0.06608098 -0.1158707 -0.05526769 0.06023448 -0.115406 -0.03840523 0.0721634 -0.1165794 -0.03482115 0.07418459 -0.1168289 -0.04731464 0.06676113 -0.1159594 -0.02510821 0.07792258 -0.1175052 -0.02278363 0.07880812 -0.1176623 -0.01695555 0.08009493 -0.1180536 -0.01131248 0.08126497 -0.1184326 -0.003539562 0.08199107 -0.1189545 0.001224577 0.08207839 -0.1192744 0.03091067 0.08042132 -0.1212677 0.09443384 0.07699275 -0.1255385 0.1346578 0.07503962 -0.1278742 0.1898546 0.07259982 -0.1310701 0.2545811 0.07011222 -0.1341999 0.317406 0.06809383 -0.1365387 0.3758929 0.06651711 -0.1379619 0.4451958 0.06509345 -0.1385692 0.481192 0.06448191 -0.1381046 0.5270413 0.06418848 -0.1375409 0.5479781 0.06449639 -0.1370122 0.5750538 0.06540286 -0.1363031 0.5939932 0.06642591 -0.1358072 0.5957614 0.06661039 -0.135761 0.601691 0.06663489 -0.1356057 0.6063902 0.06635588 -0.1354826 0.6130304 0.06538093 -0.1353087 0.6200117 0.06362098 -0.1351258 0.6240146 0.06215429 -0.135021 0.6300519 0.05949306 -0.134863 0.6378296 0.05488049 -0.1346593 0.6460101 0.04824995 -0.1344451 0.6488403 0.04542958 -0.134371 0.6536687 0.03955996 -0.1342446 0.6566618 0.03500884 -0.1341662 0.6586215 0.03178381 -0.1341148 0.6619058 0.02477729 -0.1340289 0.6631422 0.02118694 -0.1339964 0.6645712 0.01658558 -0.133959 0.6655756 0.01167231 -0.1339327 0.6661338 0.008367478 -0.1339182 0.66655 0.002978384 -0.1339073 0.6666762 -3.90294e-4 -0.133904 0.6661751 -0.008269846 -0.1339171 0.6651993 -0.01350975 -0.1339426 0.6638173 -0.01905781 -0.1339788 0.6612527 -0.02611088 -0.134046 0.6581913 -0.03252303 -0.1341261 0.6535029 -0.0397706 -0.1342489 0.6463547 -0.04781377 -0.1344361 0.639045 -0.05397003 -0.1346275 0.6348962 -0.056773 -0.1347361 0.6265223 -0.0612092 -0.1349554 0.616291 -0.06458461 -0.1352233 0.6093158 -0.06604903 -0.135406 0.6035042 -0.06663203 -0.1355581 0.6 -0.06686323 -0.1356499 0.592988 -0.06630468 -0.1358335 0.5964483 -0.06663399 -0.1357429 0.5864757 -0.06533855 -0.1360041 0.5670389 -0.06220102 -0.136513 0.5340594 -0.0588411 -0.1373924 0.5090229 -0.05798214 -0.1377436 0.4418964 -0.05797636 -0.138572 0.3745279 -0.05953496 -0.1379299 0.3168303 -0.06126475 -0.136518 0.2578019 -0.06374436 -0.1343321 0.1952924 -0.06708604 -0.1313502 0.1519711 -0.06985312 -0.128876 0.09360295 -0.07426881 -0.1254808 0.01135629 -0.08170866 -0.1199548 0.009490668 -0.08268278 -0.145 0.001016199 -0.0830093 -0.145 0.00981301 -0.08196681 -0.125 0.003704011 -0.08208942 -0.1194409 0.00101906 -0.08231061 -0.125 -0.007792651 -0.08259552 -0.145 -0.01419669 -0.08176982 -0.145 -0.02132958 -0.08018714 -0.145 -0.0282548 -0.07799208 -0.145 -0.03988862 -0.07271879 -0.145 -0.04991894 -0.066325 -0.145 -0.06045937 -0.05691045 -0.145 -0.06785881 -0.04727989 -0.145 -0.06676894 -0.04710131 -0.1146056 -0.06731927 -0.04683578 -0.125 -0.06090009 -0.05460011 -0.115014 -0.05994534 -0.05643308 -0.125 -0.05969089 -0.05619674 -0.1150982 0.5345081 -0.05773401 -0.2099729 0.5490577 -0.05933731 -0.2056003 0.5688245 -0.06172418 -0.1992033 0.5930214 -0.06589341 -0.1910734 0.6 -0.06653505 -0.1887179 0.6090244 -0.06591874 -0.1856715 0.61626 -0.06446897 -0.1832002 0.6264482 -0.06128644 -0.1797201 0.6349583 -0.05687618 -0.176822 0.6391498 -0.05410879 -0.1754009 0.6465421 -0.04800546 -0.1729077 0.6535965 -0.04015564 -0.1705483 0.6585074 -0.03269803 -0.1689214 0.6616739 -0.0262888 -0.1678806 0.6642852 -0.01920086 -0.1670288 0.6656949 -0.0136134 -0.1665692 0.6667393 -0.007526457 -0.1662296 0.6671381 -0.001662433 -0.166101 0.6670916 0.002842068 -0.1661161 0.666287 0.01065325 -0.166376 0.6649878 0.01674348 -0.1667997 0.6627451 0.02374827 -0.1675304 0.6596342 0.0306462 -0.1685513 0.6569936 0.03523313 -0.1694225 0.6538422 0.03984761 -0.170469 0.6502513 0.04421561 -0.1716654 0.6462361 0.04845267 -0.1730107 0.6384708 0.05462318 -0.1756308 0.6333692 0.05781966 -0.177362 0.6259851 0.06142073 -0.1798784 0.6188519 0.06383192 -0.1823151 0.6139689 0.0650134 -0.1839827 0.6090994 0.06581008 -0.1856461 0.6029577 0.06632173 -0.1877195 0.5977017 0.06626754 -0.1894937 0.5736168 0.06467479 -0.1976241 0.5482584 0.06352978 -0.2058571 0.5219433 0.06287056 -0.213735 0.5040354 0.06282609 -0.219097 0.4639225 0.06290805 -0.2294489 0.4139493 0.06350326 -0.2396121 0.379368 0.06408786 -0.2446313 0.3430303 0.06491112 -0.2479929 0.331 0.06525224 -0.2485268 0.331 0.06558507 -0.239 0.2890002 0.06689077 -0.239 0.289 0.06654864 -0.2490144 0.2741904 0.06704968 -0.2488127 0.2488904 0.06801784 -0.2472416 0.2217482 0.06915885 -0.2445277 0.1863781 0.07081919 -0.2393903 0.1418612 0.07314825 -0.2307279 0.09298193 0.07605838 -0.2188065 0.0491299 0.07889956 -0.2066191 0.03171879 0.08011156 -0.2015545 0.006571412 0.08187025 -0.1942322 -0.001334846 0.08224344 -0.1919504 -0.0113511 0.08152103 -0.1891649 -0.02289623 0.07919073 -0.1859506 -0.03555721 0.07450616 -0.1824257 -0.048945 0.06670141 -0.1787284 -0.06096863 0.0561496 -0.1757976 -0.07083493 0.04319769 -0.1733745 -0.07674336 0.03173065 -0.171921 -0.08087384 0.01928907 -0.1709885 -0.08280009 0.006882607 -0.1705627 -0.08280009 -0.004944443 -0.1705627 -0.08122229 -0.01668226 -0.1709115 -0.0775786 -0.02923244 -0.1717178 -0.06962639 -0.04476892 -0.1736713 -0.06030619 -0.05676817 -0.1759603 -0.04960954 -0.06617325 -0.178556 -0.03970062 -0.07237184 -0.1812721 -0.02807307 -0.07751822 -0.1845093 -0.02118051 -0.07963258 -0.1864283 -0.01408576 -0.08113616 -0.1884035 -0.005077123 -0.0821076 -0.1909115 0.003526806 -0.08217018 -0.193336 0.0113548 -0.08168846 -0.195625 0.04862904 -0.07784277 -0.2064782 0.5489376 -0.02019953 -0.205646 0.5468283 -0.01365214 -0.206284 0.5455465 -0.006879031 -0.2066678 0.5060292 0.002678751 -0.2185 0.5451171 0 -0.2067964 0.5060292 0.005321204 -0.2185 0.5468283 0.01365214 -0.206284 0.5455465 0.006879031 -0.2066678 0.5048825 0.008011579 -0.2188478 0.5489372 0.02019822 -0.2056469 0.05302244 0.04774159 -0.2076995 0.04778242 0.05303639 -0.2062388 0.05302244 -0.04774159 -0.2076995 0.04777348 -0.05304509 -0.206232 0.05769473 -0.04191768 -0.2089982 0.06173479 -0.03564256 -0.210121 0.06509989 -0.0289843 -0.2110565 0.0677545 -0.02201473 -0.2117944 0.06967085 -0.01480901 -0.212327 0.07082879 -0.007444381 -0.2126489 0.0712161 0 -0.2127565 0.09187942 0.005321204 -0.2185 0.09187942 0.002678751 -0.2185 0.07082879 0.007444381 -0.2126489 0.09307003 0.007935762 -0.21883 0.06967085 0.01480901 -0.212327 0.0677545 0.02201473 -0.2117944 0.06509989 0.0289843 -0.2110565 0.06173479 0.03564256 -0.210121 0.05769473 0.04191768 -0.2089982 -0.07081228 -0.04088348 -0.1143243 -0.07468926 -0.03325378 -0.1140545 -0.0812937 0.008544266 -0.113595 -0.07995843 0.01699566 -0.1136879 -0.07774901 0.02526217 -0.1138416 -0.07468926 0.03325378 -0.1140545 -0.07081228 0.04088348 -0.1143243 -0.04091984 0.07087528 -0.1164044 0.009614348 0.08136838 -0.1198611 0 0.08193725 -0.1191922 0.009629607 -0.08136624 -0.119859 -0.008562624 0.0814684 -0.1186172 -0.001462161 -0.08201062 -0.119094 -0.00862503 -0.08152139 -0.118613 -0.01403546 -0.08084875 -0.1182497 -0.01702737 -0.08010762 -0.1180488 -0.02108252 -0.07926815 -0.1177765 -0.02694547 -0.07740443 -0.1173784 0.01203 -0.04853117 -0.12 0.01203 0.04853117 -0.12 0.1728174 3.90638e-4 -0.1300821 0.1423976 4.36728e-4 -0.128322 0.1666633 0.04554373 -0.1297261 0.171246 0.02317237 -0.1299912 0.1591506 0.06710851 -0.1292914 0.1313272 0.05525243 -0.1276814 0.1411152 0.01914036 -0.1282477 0.137404 0.03751695 -0.1280331 0.5102395 -0.02002912 -0.1377277 0.5083052 -0.006065547 -0.1377529 0.4793758 -0.02660012 -0.1381282 0.5083052 0.005595922 -0.1377529 0.5099461 0.01816022 -0.1377316 0.4772628 -0.01349103 -0.1381556 0.5133799 0.03081399 -0.1376871 0.4765535 4.67574e-4 -0.1381648 0.4835496 0.04109609 -0.138074 0.4774179 0.0145784 -0.1381536 0.4796909 0.02763319 -0.1381241 0.5793575 -0.06353092 -0.1361905 0.5715547 -0.06044924 -0.1363947 0.5641992 -0.05641311 -0.1365874 0.557407 -0.05148601 -0.1367653 0.5512859 -0.04574561 -0.1369256 0.5459326 -0.03928226 -0.1370657 0.5414319 -0.03219801 -0.1371836 0.5378552 -0.02460479 -0.1372773 0.5352592 -0.0166226 -0.1373451 0.5336849 -0.008377552 -0.1373864 0.5874843 0.06560981 -0.1359777 0.5793575 0.06353092 -0.1361905 0.5715547 0.06044924 -0.1363947 0.5641992 0.05641311 -0.1365874 0.5512859 0.04574561 -0.1369256 0.557407 0.05148601 -0.1367653 0.5336849 0.008377552 -0.1373864 0.5352592 0.0166226 -0.1373451 0.5378552 0.02460479 -0.1372773 0.5414319 0.03219801 -0.1371836 0.5459326 0.03928226 -0.1370657 0.5331573 0 -0.1374003 0.6125115 0.06558728 -0.1353223 0.604193 0.0666458 -0.1355401 0.6357657 0.05635774 -0.1347134 0.6284231 0.06040209 -0.1349056 0.6425433 0.05142593 -0.1345359 0.6486491 -0.04568451 -0.134376 0.6425433 -0.05142593 -0.1345359 0.6357657 -0.05635774 -0.1347134 0.6284231 -0.06040209 -0.1349056 0.662039 -0.02456295 -0.1340253 0.664626 -0.01659309 -0.1339576 0.6125115 -0.06558728 -0.1353223 0.6206307 -0.06349492 -0.1351097 -0.001042068 -0.08690881 -0.125 -0.01005953 -0.09223347 -0.125 -0.007726728 -0.08189982 -0.125 -0.04720753 -0.1234833 -0.125 -0.04254722 -0.1221469 -0.125 -0.05155801 -0.1234833 -0.125 -0.03805798 -0.1192316 -0.125 -0.01494324 -0.09578168 -0.125 -0.01407617 -0.08108121 -0.125 -0.0354368 -0.1163205 -0.125 -0.05682194 -0.121983 -0.125 -0.02079671 -0.1005218 -0.125 -0.02114808 -0.079512 -0.125 -0.06164193 -0.118736 -0.125 -0.0266776 -0.1060058 -0.125 -0.02800428 -0.07733887 -0.125 -0.06412994 -0.1159114 -0.125 -0.06672877 -0.1096453 -0.125 -0.03071689 -0.1104919 -0.125 -0.06746029 -0.1040477 -0.125 -0.03955507 -0.07210314 -0.125 -0.06828212 -0.09060776 -0.125 -0.04949587 -0.06576639 -0.125 -0.06828367 -0.07609313 -0.125 -2.13206e-4 -0.08706921 -0.145 -0.009770214 -0.09267061 -0.145 -0.05163121 -0.124007 -0.145 -0.03749787 -0.1194754 -0.145 -0.04232764 -0.1226288 -0.145 -0.04713392 -0.124007 -0.145 -0.01462429 -0.09619736 -0.145 -0.05704551 -0.1224639 -0.145 -0.02045291 -0.1009173 -0.145 -0.06199043 -0.1191328 -0.145 -0.0263037 -0.1063732 -0.145 -0.06723892 -0.1097822 -0.145 -0.06458038 -0.1161924 -0.145 -0.06796699 -0.1042472 -0.145 -0.03031849 -0.1108321 -0.145 -0.06874066 -0.09122169 -0.145 -0.06883174 -0.07756185 -0.145 -0.0551272 -0.06038141 -0.1154158 -0.05284857 -0.06233054 -0.1155743 -0.04910314 -0.06555473 -0.1158351 0.5704917 -0.04652822 -0.1986473 0.5649102 -0.04241621 -0.2004518 0.5599019 -0.03765463 -0.2020777 0.5555288 -0.03231018 -0.2034975 0.5518573 -0.02646666 -0.2046894 0.6034778 -0.05527871 -0.187544 0.610389 -0.05446738 -0.1852064 0.596526 -0.05521726 -0.1898905 0.5896443 -0.05428659 -0.1922132 0.5829404 -0.05250412 -0.1944762 0.5765186 -0.04990053 -0.1966438 0.6236599 -0.05027967 -0.1806731 0.6298044 -0.0469644 -0.1785752 0.6171536 -0.05279314 -0.1828951 0.6354879 -0.04289764 -0.1766421 0.6406179 -0.03814268 -0.1749042 0.6451106 -0.03277432 -0.1733886 0.6488915 -0.02687829 -0.1721211 0.6518993 -0.02054834 -0.1711144 0.6540839 -0.01388633 -0.1703888 0.6554093 -0.00699979 -0.1699486 0.6554093 0.00699979 -0.1699486 0.6540839 0.01388633 -0.1703888 0.6518993 0.02054828 -0.1711143 0.6558536 0 -0.1698011 0.6488911 0.02687907 -0.1721203 0.6451103 0.0327745 -0.1733903 0.640618 0.03814262 -0.1749042 0.6354879 0.04289764 -0.1766421 0.6298044 0.0469644 -0.1785752 0.6236599 0.05027967 -0.1806731 0.6171536 0.05279314 -0.1828951 0.6103881 0.05446749 -0.1852073 0.6034778 0.05527871 -0.187544 0.596526 0.05521726 -0.1898905 0.5896443 0.05428659 -0.1922132 0.5829404 0.05250412 -0.1944762 0.5765186 0.04990053 -0.1966438 0.5704922 0.04652857 -0.1986458 0.5649102 0.04241621 -0.2004518 0.5599019 0.03765463 -0.2020777 0.5555288 0.03231018 -0.2034975 0.5518573 0.02646666 -0.2046894 0.5012506 0.01153993 -0.2198154 0.4938138 0.01527458 -0.2217341 0.4877935 0.01741236 -0.2232872 0.4769988 0.0202319 -0.2260721 0.4639285 0.02248251 -0.2294471 0.44766 0.02397358 -0.232763 0.4274788 0.02487558 -0.2368628 0.4140283 0.02504026 -0.2395968 0.3965647 0.02487558 -0.2421371 0.3793609 0.0244022 -0.2446321 0.3563659 0.03863406 -0.2467589 0.3593659 0.02381229 -0.2464814 0.3563652 0.02695196 -0.2467461 0.3533659 0.04163408 -0.2470366 0.3430334 0.04163408 -0.2479926 0.331 0.04463404 -0.2485268 0.334 0.04163408 -0.2483935 0.331 0.04463404 -0.239 0.289 0.04463404 -0.239 0.3533659 0.04163408 -0.239 0.3563659 0.03863412 -0.239 0.3077545 0.04398936 -0.239 0.3071542 0.04300945 -0.239 0.307 0.04199999 -0.239 0.3072007 0.04086792 -0.239 0.3563659 0.02803176 -0.239001 0.286 0.04163408 -0.239 0.3593642 0.02503716 -0.2390176 0.3080025 0.03974491 -0.239 0.3089362 0.03919494 -0.239 0.334 0.04163408 -0.239 0.2666341 0.04163408 -0.239 0.2636341 0.03863406 -0.239 0.2636341 0.02501636 -0.2390005 0.3119525 0.04430317 -0.239 0.3100656 0.03898119 -0.239 0.3110638 0.03919494 -0.239 0.3127992 0.043132 -0.239 0.3110638 0.04480504 -0.239 0.3099344 0.04501873 -0.239 0.313 0.04199999 -0.239 0.3128166 0.0409314 -0.239 0.308539 0.04464244 -0.239 0.3120507 0.03978377 -0.239 0.289 0.04463404 -0.2490144 0.274191 0.04163408 -0.2488127 0.286 0.04163408 -0.2489735 0.2636341 0.03863406 -0.2481571 0.2636339 0.02318704 -0.2481459 0.2488613 0.02356606 -0.2472397 0.2666341 0.04163408 -0.2483434 0.2219264 0.02442044 -0.2445478 0.205287 0.02487558 -0.2421371 0.1864716 0.02503794 -0.2394063 0.1733862 0.02487558 -0.2368628 0.1600423 0.02438044 -0.2342672 0.1431451 0.02322936 -0.2309921 0.1362692 0.02243882 -0.2293632 0.1271206 0.02102291 -0.2271321 0.1141696 0.01825726 -0.2239738 0.1021378 0.01414859 -0.2210396 0.09577667 0.01050215 -0.2194883 0.04198634 0.05778926 -0.2045441 0.03573954 0.06190276 -0.2027253 0.0290938 0.06534582 -0.2007902 0.02212041 0.06807959 -0.1987597 0.01489442 0.07007282 -0.1966557 0.007494091 0.07130205 -0.1945009 1.16373e-5 0.07175147 -0.1923266 -0.007505834 0.07141327 -0.1902354 -0.01494067 0.07029056 -0.1881655 -0.02222263 0.06839436 -0.186138 -0.029271 0.0657438 -0.1841758 -0.03600734 0.06236654 -0.1823004 -0.04235643 0.05829864 -0.1805326 -0.04819947 0.0536226 -0.178929 -0.04819947 -0.0536226 -0.178929 -0.05360883 -0.04826962 -0.1776051 -0.05838561 -0.04241961 -0.176432 -0.06252288 -0.03609758 -0.1754159 -0.06597393 -0.02937346 -0.1745682 -0.06869959 -0.02232182 -0.1738989 -0.07066893 -0.01502114 -0.1734153 -0.07185953 -0.007552742 -0.1731229 -0.07225793 0 -0.173025 -0.06597393 0.02937346 -0.1745682 -0.06869959 0.02232182 -0.1738989 -0.07066893 0.01502114 -0.1734153 -0.07185953 0.007552742 -0.1731229 -0.05838561 0.04241961 -0.176432 -0.06252288 0.03609758 -0.1754159 -0.05360883 0.04826962 -0.1776051 1.39468e-5 -0.07175135 -0.1923264 -0.007505834 -0.07141327 -0.1902354 -0.01494067 -0.07029056 -0.1881655 -0.02222263 -0.06839436 -0.186138 -0.029271 -0.0657438 -0.1841758 -0.03600734 -0.06236654 -0.1823004 -0.04235643 -0.05829864 -0.1805326 0.04198634 -0.05778926 -0.2045441 0.03573954 -0.06190276 -0.2027253 0.0290938 -0.06534582 -0.2007902 0.02212041 -0.06807959 -0.1987597 0.01489442 -0.07007282 -0.1966557 0.007494091 -0.07130205 -0.1945009 0.5456521 -0.01395416 -0.16 0.5478296 -0.02065569 -0.16 0.5478296 0.02065569 -0.16 0.5456521 0.01395416 -0.16 0.5443317 0.007032513 -0.16 0.5438893 0 -0.16 0.5443317 -0.007032513 -0.16 0.05395191 -0.0485785 -0.16 0.0485785 -0.05395191 -0.16 0.05873417 -0.04267287 -0.16 0.062873 -0.0362997 -0.16 0.06632292 -0.02952885 -0.16 0.06904619 -0.02243447 -0.16 0.07101297 -0.01509428 -0.16 0.07220178 -0.007588684 -0.16 0.07259947 0 -0.16 0.07220178 0.007588684 -0.16 0.07101297 0.01509428 -0.16 0.06904619 0.02243447 -0.16 0.06632292 0.02952885 -0.16 0.062873 0.0362997 -0.16 0.05873417 0.04267287 -0.16 0.05395191 0.0485785 -0.16 0.0485785 0.05395191 -0.16 -0.07762122 -0.02522063 -0.11 -0.07455974 -0.03319609 -0.11 -0.07068133 -0.0408079 -0.11 -0.06602853 -0.04797255 -0.11 -0.07983231 -0.01696884 -0.11 -0.08116871 -0.008531153 -0.11 -0.0816158 0 -0.11 -0.08116871 0.008531153 -0.11 -0.07983231 0.01696884 -0.11 -0.07762122 0.02522063 -0.11 -0.07455974 0.03319609 -0.11 -0.07068133 0.0408079 -0.11 -0.06602853 0.04797255 -0.11 -0.06065237 0.05461162 -0.11 -0.05461162 0.06065237 -0.11 -0.04797255 0.06602853 -0.11 -0.0408079 0.07068133 -0.11 -0.03319609 0.07455974 -0.11 -0.02522063 0.07762122 -0.11 -0.01696884 0.07983231 -0.11 -0.008531153 0.08116871 -0.11 0 0.0816158 -0.11 0.008531153 0.08116871 -0.11 0.01696884 0.07983231 -0.11 0.01704156 0.08017432 -0.12 0.04116624 0.02837842 -0.12 0.07098418 0.04098272 -0.12 0.04675716 0.0177133 -0.12 0.06091219 0.05484557 -0.12 0.06631147 0.04817807 -0.12 0.03318762 0.03739756 -0.12 0.05484557 0.06091219 -0.12 0.04817807 0.06631147 -0.12 0.02328407 0.04424756 -0.12 0.04098272 0.07098418 -0.12 0.03333836 0.07487916 -0.12 0.02532869 0.07795381 -0.12 0.03318762 -0.03739756 -0.12 0.06091219 -0.05484557 -0.12 0.05484557 -0.06091219 -0.12 0.04817807 -0.06631147 -0.12 0.04116624 -0.02837842 -0.12 0.07098418 -0.04098272 -0.12 0.06631147 -0.04817807 -0.12 0.02328407 -0.04424756 -0.12 0.04098272 -0.07098418 -0.12 0.03333836 -0.07487916 -0.12 0.02532869 -0.07795381 -0.12 0.04675716 -0.0177133 -0.12 0.08017432 -0.01704156 -0.12 0.07795381 -0.02532869 -0.12 0.07487916 -0.03333836 -0.12 0.01704156 -0.08017432 -0.12 0.04963612 -0.006020843 -0.12 0.0819655 0 -0.12 0.08151644 -0.00856769 -0.12 0.04963612 0.006020843 -0.12 0.08017432 0.01704156 -0.12 0.08151644 0.00856769 -0.12 0.07487916 0.03333836 -0.12 0.07795381 0.02532869 -0.12 -0.01044547 -0.04889672 -0.12 8.13081e-4 -0.04999333 -0.12 -0.03887331 -0.03144615 -0.12 -0.02116942 -0.04529738 -0.12 -0.03080987 -0.03937953 -0.12 -0.04494714 -0.02190321 -0.12 -0.04872041 -0.01123923 -0.12 8.13081e-4 0.04999333 -0.12 -0.04999995 0 -0.12 -0.01044547 0.04889672 -0.12 -0.02116942 0.04529738 -0.12 -0.04872041 0.01123923 -0.12 -0.04494714 0.02190321 -0.12 -0.03080987 0.03937953 -0.12 -0.03887331 0.03144615 -0.12 0.008531153 -0.08116871 -0.11 0.01696884 -0.07983231 -0.11 0 -0.0816158 -0.11 -0.008531153 -0.08116871 -0.11 -0.01696884 -0.07983231 -0.11 -0.02522063 -0.07762122 -0.11 -0.03114026 -0.07561391 -0.1170849 0.1572077 0.06574666 -0.1104083 0.164417 0.04476916 -0.1104156 0.1688393 0.02303254 -0.1104156 0.1703997 9.05811e-4 -0.1104085 0.1488658 7.12038e-4 -0.1173075 0.1574954 0.00120455 -0.09899997 0.1536661 0.00118941 -0.09957677 0.1494244 0.001130938 -0.1018091 0.1464438 0.001043319 -0.1051559 0.1453502 9.85451e-4 -0.1073672 0.1445941 9.05622e-4 -0.1104156 0.1509306 5.93283e-4 -0.1197155 0.1536229 6.04743e-4 -0.1213583 0.1567023 5.90316e-4 -0.1220943 0.1651917 6.91509e-4 -0.118569 0.1690677 0.001019299 -0.106074 0.1658592 0.001124739 -0.1020471 0.1616547 0.001186609 -0.09968322 0.162782 6.17453e-4 -0.12063 0.1598581 5.86182e-4 -0.1218433 0.1432638 0.01958972 -0.1104156 0.1395293 0.03794515 -0.1104156 0.1334534 0.05566376 -0.1104156 0.150079 0.0630452 -0.12063 0.1523368 0.06390547 -0.1185625 0.1473804 0.06192398 -0.1218429 0.144479 0.06068259 -0.1220944 0.1560259 0.06512171 -0.106074 0.1391716 0.05840224 -0.1197128 0.1416455 0.05948042 -0.1213597 0.1531137 0.063771 -0.1020471 0.1373109 0.0575115 -0.1173092 0.1492676 0.06207114 -0.09968322 0.1454459 0.06042951 -0.09899997 0.1419151 0.0589472 -0.09957677 0.1341806 0.05588573 -0.1073672 0.1352099 0.05625969 -0.1051559 0.1379879 0.05734372 -0.1018091 0.5106251 0.03091114 -0.1069942 0.5073021 0.01868969 -0.106981 0.505613 0.005771219 -0.106981 0.505613 -0.006251335 -0.106981 0.507493 -0.01978874 -0.1069942 0.4889772 -0.02411681 -0.1187959 0.4904256 -0.02380412 -0.1206304 0.4923754 -0.02342045 -0.1219283 0.4881261 -0.02420622 -0.116577 0.4946175 -0.02294933 -0.1225495 0.4969371 -0.02245223 -0.1224326 0.4829788 -0.02497923 -0.1069384 0.4879892 -0.02414822 -0.114194 0.4991055 -0.02198886 -0.1215904 0.5009078 -0.02157962 -0.1201064 0.5021709 -0.02126282 -0.1181229 0.502762 -0.0210241 -0.1158053 0.4810983 -0.01308631 -0.1067916 0.4804116 4.47526e-4 -0.1067916 0.4812484 0.01412969 -0.1067916 0.483446 0.02677208 -0.1067916 0.4869254 0.03905069 -0.1069384 0.5047629 0.03332555 -0.1194741 0.5031836 0.03388386 -0.1211454 0.5011922 0.03459906 -0.1222224 0.5057703 0.03294968 -0.1173821 0.498974 0.0353592 -0.1225935 0.4967564 0.03612256 -0.1222223 0.5060881 0.03269648 -0.115 0.4947483 0.0367884 -0.1211453 0.4931675 0.03733444 -0.1194778 0.4921174 0.03761148 -0.1173643 0.4917285 0.03764086 -0.115 0.5794786 -0.06315851 -0.125 0.5875562 -0.06523251 -0.125 0.5717245 -0.06008845 -0.125 0.5644164 -0.0560708 -0.125 0.5576694 -0.05116885 -0.125 0.55159 -0.04545992 -0.125 0.5462742 -0.03903406 -0.125 0.5418055 -0.03199267 -0.125 0.5382546 -0.02444672 -0.125 0.5356776 -0.01651519 -0.125 0.5341149 -0.008323192 -0.125 0.5335912 0 -0.125 0.5341149 0.008323192 -0.125 0.5356776 0.01651519 -0.125 0.5382546 0.02444672 -0.125 0.5418055 0.03199267 -0.125 0.5462742 0.03903406 -0.125 0.55159 0.04545992 -0.125 0.5576694 0.05116885 -0.125 0.5644164 0.0560708 -0.125 0.5717245 0.06008845 -0.125 0.5794786 0.06315851 -0.125 0.5875562 0.06523251 -0.125 0.5958301 0.06627774 -0.125 0.6282755 0.06008845 -0.125 0.6205214 0.06315851 -0.125 0.6041699 0.06627774 -0.125 0.6124438 0.06523251 -0.125 0.6423306 0.05116885 -0.125 0.6355836 0.0560708 -0.125 0.64841 0.04545992 -0.125 0.6581945 0.03199267 -0.125 0.6537258 0.03903406 -0.125 0.6643224 0.01651519 -0.125 0.6617454 0.02444672 -0.125 0.6658851 0.008323192 -0.125 0.6664088 0 -0.125 0.6205214 -0.06315851 -0.125 0.6282755 -0.06008845 -0.125 0.6658851 -0.008323192 -0.125 0.6643224 -0.01651519 -0.125 0.6617454 -0.02444672 -0.125 0.6581945 -0.03199267 -0.125 0.6537258 -0.03903406 -0.125 0.64841 -0.04545992 -0.125 0.6423306 -0.05116885 -0.125 0.6355836 -0.0560708 -0.125 0.6041699 -0.06627774 -0.125 0.6124438 -0.06523251 -0.125 0.5958301 -0.06627774 -0.125 -0.03373003 -0.0745303 -0.1169047 -0.03983211 -0.07156294 -0.1164801 -0.06065237 -0.05461162 -0.11 -0.05461162 -0.06065237 -0.11 0.5508298 -0.02703154 -0.16 0.5546055 -0.03298103 -0.16 0.559097 -0.03841042 -0.16 0.5642337 -0.04323405 -0.16 0.5699344 -0.04737579 -0.16 0.5761092 -0.05077046 -0.16 0.5826608 -0.05336445 -0.16 0.5894859 -0.05511683 -0.16 0.5964768 -0.05599999 -0.16 0.6035232 -0.05599999 -0.16 0.6105141 -0.05511683 -0.16 0.6173392 -0.05336445 -0.16 0.6238908 -0.05077046 -0.16 0.6300656 -0.04737579 -0.16 0.6357663 -0.04323405 -0.16 0.640903 -0.03841042 -0.16 0.6453945 -0.03298103 -0.16 0.6491702 -0.02703154 -0.16 0.6521704 -0.02065569 -0.16 0.6543479 -0.01395416 -0.16 0.6556683 -0.007032513 -0.16 0.6561107 0 -0.16 0.6556683 0.007032513 -0.16 0.6543479 0.01395416 -0.16 0.6521704 0.02065569 -0.16 0.6491702 0.02703154 -0.16 0.6453945 0.03298103 -0.16 0.640903 0.03841042 -0.16 0.6357663 0.04323405 -0.16 0.6300656 0.04737579 -0.16 0.6238908 0.05077046 -0.16 0.6173392 0.05336445 -0.16 0.6105141 0.05511683 -0.16 0.6035232 0.05599999 -0.16 0.5964768 0.05599999 -0.16 0.5894859 0.05511683 -0.16 0.5826608 0.05336445 -0.16 0.5761092 0.05077046 -0.16 0.5699344 0.04737579 -0.16 0.5642337 0.04323405 -0.16 0.559097 0.03841042 -0.16 0.5546055 0.03298103 -0.16 0.5508298 0.02703154 -0.16 0.3593659 0.02487558 -0.2421371 0.3593659 0.02438044 -0.2447327 0.3563659 0.02785778 -0.2425138 0.2636341 0.02487558 -0.2421371 0.2636341 0.02438044 -0.2447327 0.3082958 0.03953105 -0.229 0.3092791 0.03907495 -0.229 0.3129906 0.04236286 -0.229 0.3106588 0.03905326 -0.229 0.3126564 0.04339414 -0.229 0.3120507 0.04421621 -0.229 0.3119525 0.03969681 -0.229 0.3128309 0.04092603 -0.229 0.3110638 0.04480504 -0.229 0.3100656 0.04501873 -0.229 0.3089362 0.04480504 -0.229 0.3080474 0.04430317 -0.229 0.3072007 0.043132 -0.229 0.3069953 0.04170143 -0.229 0.3074782 0.04033935 -0.229 0.01509428 0.07101297 -0.16 0.007588684 0.07220178 -0.16 0 0.07259947 -0.16 0.04267287 0.05873417 -0.16 0.0362997 0.062873 -0.16 0.02952885 0.06632292 -0.16 0.02243447 0.06904619 -0.16 -0.0362997 0.062873 -0.16 -0.04267287 0.05873417 -0.16 -0.0485785 0.05395191 -0.16 -0.007588684 0.07220178 -0.16 -0.01509428 0.07101297 -0.16 -0.02243447 0.06904619 -0.16 -0.02952885 0.06632292 -0.16 -0.05395191 -0.0485785 -0.16 -0.0485785 -0.05395191 -0.16 -0.04267287 -0.05873417 -0.16 -0.05395191 0.0485785 -0.16 -0.05873417 0.04267287 -0.16 -0.062873 0.0362997 -0.16 -0.06632292 0.02952885 -0.16 -0.06904619 0.02243447 -0.16 -0.07101297 0.01509428 -0.16 -0.07220178 0.007588684 -0.16 -0.07259947 0 -0.16 -0.07220178 -0.007588684 -0.16 -0.07101297 -0.01509428 -0.16 -0.06904619 -0.02243447 -0.16 -0.06632292 -0.02952885 -0.16 -0.062873 -0.0362997 -0.16 -0.05873417 -0.04267287 -0.16 -0.007588684 -0.07220178 -0.16 0 -0.07259947 -0.16 0.007588684 -0.07220178 -0.16 -0.0362997 -0.062873 -0.16 -0.02952885 -0.06632292 -0.16 -0.02243447 -0.06904619 -0.16 -0.01509428 -0.07101297 -0.16 0.04267287 -0.05873417 -0.16 0.01509428 -0.07101297 -0.16 0.02243447 -0.06904619 -0.16 0.02952885 -0.06632292 -0.16 0.0362997 -0.062873 -0.16 -0.006026804 -0.04963541 -0.11 0.006026804 -0.04963541 -0.11 -0.04854708 -0.01196575 -0.11 -0.04999995 0 -0.11 0.006026804 0.04963541 -0.11 0.04999995 0 -0.11 0.08116871 0.008531153 -0.11 0.04854708 0.01196575 -0.11 0.07983231 0.01696884 -0.11 0.07762122 0.02522063 -0.11 -0.006026804 0.04963541 -0.11 -0.04854708 0.01196575 -0.11 -0.01773023 -0.04675078 -0.11 -0.0408079 -0.07068133 -0.11 -0.03319609 -0.07455974 -0.11 0.04427278 0.02323615 -0.11 0.07455974 0.03319609 -0.11 0.07068133 0.0408079 -0.11 -0.01773023 0.04675078 -0.11 0.06602853 0.04797255 -0.11 -0.04797255 -0.06602853 -0.11 -0.02840322 -0.04114913 -0.11 -0.04427278 0.02323615 -0.11 0.06065237 0.05461162 -0.11 0.03742551 0.03315609 -0.11 -0.03742551 -0.03315609 -0.11 0.05461162 0.06065237 -0.11 0.02840322 0.04114913 -0.11 -0.02840322 0.04114913 -0.11 0.04797255 0.06602853 -0.11 -0.04427278 -0.02323615 -0.11 -0.03742551 0.03315609 -0.11 0.05461162 -0.06065237 -0.11 0.06065237 -0.05461162 -0.11 0.03742551 -0.03315609 -0.11 0.06602853 -0.04797255 -0.11 0.01773023 0.04675078 -0.11 0.0408079 0.07068133 -0.11 0.02840322 -0.04114913 -0.11 0.0408079 -0.07068133 -0.11 0.04797255 -0.06602853 -0.11 0.03319609 0.07455974 -0.11 0.07068133 -0.0408079 -0.11 0.04427278 -0.02323615 -0.11 0.07455974 -0.03319609 -0.11 0.07762122 -0.02522063 -0.11 0.01773023 -0.04675078 -0.11 0.02522063 0.07762122 -0.11 0.02522063 -0.07762122 -0.11 0.03319609 -0.07455974 -0.11 0.07983231 -0.01696884 -0.11 0.04854708 -0.01196575 -0.11 0.08116871 -0.008531153 -0.11 0.0816158 0 -0.11 0.163142 0.0443803 -0.106074 0.1675138 0.02289235 -0.106074 0.1600577 0.04349815 -0.1020471 0.16433 0.0224992 -0.1020471 0.1560087 0.04236656 -0.09968322 0.1601607 0.02195882 -0.09968322 0.1519992 0.04126101 -0.09899997 0.156038 0.02140986 -0.09899997 0.1522436 0.02089399 -0.09957677 0.1483049 0.04025328 -0.09957677 0.1480423 0.02030879 -0.1018091 0.1442089 0.03915035 -0.1018091 0.1450915 0.01988208 -0.1051559 0.1413261 0.03839015 -0.1051559 0.14401 0.01971703 -0.1073672 0.140266 0.03811955 -0.1073672 0.1675814 6.22887e-4 -0.1127853 0.1668448 6.11188e-4 -0.1158661 0.16733 6.69684e-4 -0.1096276 0.1661152 6.32246e-4 -0.1067021 0.1640558 6.69684e-4 -0.1042951 0.1613534 6.16202e-4 -0.1026425 0.1476445 6.32246e-4 -0.1143724 0.1582726 6.46285e-4 -0.1019058 0.1473931 6.46285e-4 -0.1112147 0.1551149 6.69684e-4 -0.1021572 0.1481299 6.46285e-4 -0.1081339 0.1521894 7.1648e-4 -0.103372 0.1497825 6.69684e-4 -0.1054314 0.1538182 0.06463563 -0.1158641 0.1545067 0.06489735 -0.1127832 0.1542893 0.06476444 -0.1096256 0.1531522 0.0643326 -0.1067003 0.1512743 0.0634846 -0.1042938 0.1487681 0.06247162 -0.1026418 0.1361467 0.05712687 -0.1143744 0.1459504 0.06122475 -0.1019057 0.1359376 0.05697453 -0.1112167 0.1430292 0.06002545 -0.1021577 0.136606 0.05728369 -0.1081358 0.1403557 0.05883717 -0.1033732 0.1381103 0.05796802 -0.1054331 0.4906768 0.03235489 -0.1019999 0.5041239 0.02772462 -0.1019999 0.50196 0.01975953 -0.1019999 0.5001772 0.006125092 -0.1019999 0.5001772 -0.006626486 -0.1019999 0.5014534 -0.01582849 -0.1019999 0.4875023 -0.01879388 -0.1019999 0.4880337 -0.02435481 -0.1141825 0.4886 -0.02402681 -0.1118896 0.4898858 -0.02382272 -0.1099012 0.4916824 -0.02337163 -0.1084119 0.4938756 -0.02300924 -0.1075675 0.4961755 -0.02241659 -0.1074506 0.4984324 -0.02200609 -0.1080728 0.502667 -0.02114057 -0.1134446 0.5018411 -0.02131617 -0.1112239 0.5003632 -0.02152645 -0.109373 0.5028025 -0.02121561 -0.1158175 0.4864922 -0.01251721 -0.1019999 0.4858358 4.1934e-4 -0.1019999 0.4866358 0.01349872 -0.1019999 0.4887324 0.02555996 -0.1019999 0.5061563 0.03289455 -0.115 0.5057708 0.03291648 -0.1126535 0.5047169 0.03316861 -0.1105367 0.5031626 0.0338146 -0.1088566 0.501127 0.03440469 -0.1077782 0.4989424 0.03526771 -0.1074064 0.4966896 0.0359326 -0.1077782 0.492114 0.03761887 -0.1126534 0.4930997 0.03716874 -0.1105367 0.4947222 0.03672081 -0.1088567 0.4917967 0.03783893 -0.115 0.6284033 -0.04114913 -0.125 0.6177302 -0.04675078 -0.125 0.6442728 0.02323615 -0.125 0.6485471 0.01196575 -0.125 0.6177302 0.04675078 -0.125 0.6284033 0.04114913 -0.125 0.5625745 0.03315609 -0.125 0.5557272 0.02323615 -0.125 0.6374255 0.03315609 -0.125 0.6374255 -0.03315609 -0.125 0.5715967 0.04114913 -0.125 0.6442728 -0.02323615 -0.125 0.5625745 -0.03315609 -0.125 0.5822698 0.04675078 -0.125 0.5715967 -0.04114913 -0.125 0.6485471 -0.01196575 -0.125 0.5557272 -0.02323615 -0.125 0.5822698 -0.04675078 -0.125 0.5939731 0.04963541 -0.125 0.5514529 -0.01196575 -0.125 0.65 0 -0.125 0.5939731 -0.04963541 -0.125 0.55 0 -0.125 0.6060269 -0.04963541 -0.125 0.5514529 0.01196575 -0.125 0.6060269 0.04963541 -0.125 0.1521894 5.7609e-4 -0.103372 0.4917246 -0.02357029 -0.1084119 0.4886422 -0.02422547 -0.1118896 0.5004055 -0.02172511 -0.109373 0.4962177 -0.02261525 -0.1074506 0.5047851 0.03336668 -0.1105367 0.5011952 0.03460276 -0.1077782 0.4967578 0.03613066 -0.1077782 0.4931679 0.0373668 -0.1105367 0.6177302 -0.04675078 -0.135 0.6060269 -0.04963541 -0.135 0.5939731 -0.04963541 -0.135 0.55 0 -0.135 0.5514529 0.01196575 -0.135 0.5822698 -0.04675078 -0.135 0.5557272 0.02323615 -0.135 0.5715967 -0.04114913 -0.135 0.5625745 -0.03315609 -0.135 0.5625745 0.03315609 -0.135 0.5557272 -0.02323615 -0.135 0.5715967 0.04114913 -0.135 0.5514529 -0.01196575 -0.135 0.5822698 0.04675078 -0.135 0.5939731 0.04963541 -0.135 0.6060269 0.04963541 -0.135 0.6177302 0.04675078 -0.135 0.6284033 0.04114913 -0.135 0.6374255 0.03315609 -0.135 0.6442728 0.02323615 -0.135 0.6485471 0.01196575 -0.135 0.65 0 -0.135 0.6485471 -0.01196575 -0.135 0.6442728 -0.02323615 -0.135 0.6374255 -0.03315609 -0.135 0.6284033 -0.04114913 -0.135 + + + + + + + + + + 3.56945e-5 1.19551e-5 -1 -2.79484e-5 -8.47301e-6 -1 2.20301e-6 6.67877e-7 -1 -1.61906e-4 -0.004625678 -0.9999894 0 -1.50641e-5 -1 0 1.28632e-5 -1 -2.37681e-6 -5.57522e-7 -1 0 -2.46616e-5 -1 -7.09707e-7 1.58098e-5 -1 -1.605e-5 -1.51541e-4 -1 0 -6.92114e-7 -1 0 -4.96712e-6 -1 0 -4.96704e-6 -1 0 -6.86722e-7 -1 2.98107e-6 5.16884e-7 -1 -3.03745e-6 3.56698e-5 -1 2.04632e-6 0 -1 0 -9.02464e-6 -1 1.82902e-7 3.11157e-7 -1 -1.99966e-7 0 -1 1.59199e-6 0 -1 0 -5.94594e-6 -1 0 -6.51612e-5 -1 2.47981e-7 -2.91213e-6 -1 0 -1.34771e-5 -1 0 1.36376e-5 -1 2.32969e-6 -5.22052e-7 -1 -4.66005e-5 -1.56079e-5 -1 0 1 0 0 1 6.12602e-7 0.7071037 0.7071099 0 0.7071083 0.7071053 -3.74564e-7 1 -3.95045e-7 0 1 1.34789e-5 -6.43443e-5 1 6.12775e-6 0 1 0 0 -5.52805e-4 0.9983499 -0.05742233 0 0.9978387 -0.06571233 2.03361e-4 0.9966961 -0.08122271 5.51913e-5 0.9979887 -0.06339269 3.76162e-7 -4.13005e-5 -1 -1 0 0 -1 -3.3615e-5 9.04268e-5 -1 -2.85567e-6 0 -0.7071034 0.7071102 0 -0.7071036 0.7071101 3.09443e-6 0 1 6.68471e-7 -0.7071083 0.7071054 0 -0.7071053 0.7071083 0 -1 6.13465e-5 -1.3884e-4 0.03181064 -0.998872 -0.03525555 0.03249013 -0.9989563 -0.03210383 0.03046488 -0.9989289 -0.03482866 0.03902041 -0.9986653 -0.03383797 0.0425418 -0.9984809 -0.03501808 0.04238194 -0.9984864 -0.03505533 0.7071082 0.7071055 0 0.7071068 0.7071068 0 0.4207137 0.9071866 -0.003546059 0.1859351 0.9825472 0.005409657 0.01576161 0.9998428 -0.008135795 -0.9846239 -0.1746041 0.005409181 -0.2093588 0.9778242 0.005374431 -0.951278 -0.3082852 -0.005508184 -0.8103975 -0.5858736 0.002860009 -0.4453469 0.8953422 -0.005353152 -0.5123636 0.8587653 0.002437472 -0.8050851 -0.5931455 0.004048883 -0.8317781 0.5551065 0.001486003 -0.4917086 -0.8707599 0 -0.512374 -0.8587591 -0.002438068 -0.813637 0.5813658 -0.002931892 -0.9855982 0.1690977 0.001497924 -0.1859259 -0.9825608 0.002438902 -0.2093552 -0.9778397 0 -0.9938696 0.1104483 -0.004943668 0.2603558 -0.9654979 0.005355298 0.1859267 -0.9825606 -0.002438247 0.4916986 -0.8707489 -0.005374789 0.6398212 -0.7685051 0.005374491 0.8527372 -0.5223346 0.002437949 0.8103905 -0.5858656 -0.005353927 0.9898453 -0.1421204 -0.00285989 0.9885211 -0.1510287 -0.004050493 0.9846221 0.1746056 0.005670785 0.942497 0.3341069 -0.008487343 0.8138638 0.5809989 0.008135497 0.703011 0.7111585 -0.005407392 0.5075698 0.8616034 0.00354588 -0.06199955 3.20928e-5 -0.9980763 -0.06203073 2.21208e-5 -0.9980743 -0.06199246 -7.10923e-6 -0.9980766 -0.06125056 7.33879e-4 -0.9981222 -0.06198686 -5.43197e-6 -0.998077 -0.01373136 0 -0.9999058 -0.01360958 2.57213e-5 -0.9999074 -0.0136246 -6.38545e-5 -0.9999072 -0.003973603 0.9439523 0.3300581 4.4913e-4 0.9518519 0.306558 -1.119e-4 0.9822871 0.1873827 0 0.9826416 0.1855142 0 0.9989944 0.04483699 -5.76388e-4 0.9984565 0.05553579 0 0.998663 0.05169498 6.94099e-4 0.9982015 0.05994462 0.1997178 1.81219e-4 -0.9798535 0.1990799 7.92776e-7 -0.9799833 0.1990793 -1.87988e-6 -0.9799834 0.1990829 -1.36079e-6 -0.9799827 0.1990793 -1.02028e-6 -0.9799835 0.1991904 -4.05497e-5 -0.9799609 0 0.9822868 -0.1873841 0 0.9822871 -0.1873824 -0.1906886 1.3717e-4 -0.9816506 -0.1910547 2.7102e-6 -0.9815794 -0.1909305 6.95271e-5 -0.9816036 -0.1892737 -6.35165e-4 -0.9819242 -0.1433838 1.17736e-4 -0.9896672 -0.1438094 -1.03559e-4 -0.9896054 -0.1436475 2.07623e-5 -0.989629 -0.7068443 0.7064073 0.03687626 -0.7083629 0.7050275 0.03403264 -0.6972683 0.7000057 0.1543016 -0.7070983 0.6945906 0.1324985 -0.7120727 0.6677423 0.2169629 0.09217441 3.32183e-5 -0.995743 0.09210979 -2.17082e-5 -0.9957489 0.09205698 9.41883e-5 -0.9957538 0.09213811 5.64884e-5 -0.9957462 0.08869546 7.14518e-4 -0.9960585 0.09209287 9.11654e-6 -0.9957504 0.04433977 2.03846e-5 -0.9990165 0.04447674 0 -0.9990105 0.04436141 -6.80037e-5 -0.9990156 0 0 -1 8.70246e-5 0 -1 -7.49449e-6 0 -1 1.11613e-4 0 -1 2.43113e-5 0 -1 2.02568e-4 0 -1 -2.39326e-5 0 -1 -1.13805e-4 0 -1 3.04374e-4 -8.03239e-5 -1 -3.15869e-4 2.23689e-5 -1 1.29942e-4 0 -1 -4.3789e-6 0 -1 1.16528e-5 0 -1 0 2.26735e-4 -1 5.29392e-6 0 -1 -1.60388e-4 -2.08305e-4 -1 2.22252e-5 0 -1 1.9658e-4 1.93964e-4 -1 -1.60307e-4 -1.82063e-4 -1 7.87211e-5 0 -1 1.64031e-5 0 -1 -7.96016e-7 0 -1 -4.8895e-5 0 -1 -1.54036e-5 0 -1 1.25585e-4 0 -1 1.56652e-5 0 -1 2.7994e-5 0 -1 3.59708e-5 0 -1 1.51681e-5 0 -1 -1.04919e-5 0 -1 -4.35428e-5 0 -1 2.96912e-6 0 -1 6.32117e-5 0 -1 -1.75523e-4 0 -1 0 5.12853e-4 -1 6.71426e-6 0 -1 -6.13442e-5 -3.85084e-4 -1 -8.44757e-5 0 -1 -3.22914e-6 0 -1 4.9641e-7 0 -1 -9.94816e-5 0 -1 5.73782e-5 0 -1 -3.15119e-5 0 -1 1.13261e-5 0 -1 0.00110799 0.002113938 -0.9999971 -7.21876e-6 0 -1 1.06246e-4 0 -1 -8.46329e-4 -0.00140208 -0.9999987 9.21458e-5 0 -1 -2.12362e-4 3.96727e-4 -1 -6.24688e-6 0 -1 3.21872e-4 -4.9575e-4 -0.9999999 -1.00639e-4 0 -1 -6.45661e-6 0 -1 -1.84988e-5 0 -1 -3.06576e-4 3.32723e-4 -1 8.29022e-6 0 -1 4.11689e-4 -3.64088e-4 -0.9999999 3.62592e-6 0 -1 4.43388e-6 0 -1 0.04309767 -0.998461 -0.03490436 4.32904e-5 0 -1 -5.99662e-5 0 -1 -4.82085e-5 -1.97602e-6 -1 0 1.74194e-6 -1 4.94451e-5 -2.62008e-6 -1 -2.22345e-5 1.79068e-6 -1 0 2.58782e-6 -1 0 2.68475e-6 -1 2.38512e-5 -1.92087e-6 -1 1.66355e-4 4.00251e-5 -1 -5.15323e-5 3.23767e-7 -1 0.04817074 -0.9982372 -0.03467196 0.04996603 -0.9981337 -0.0351094 -0.09953486 -4.19547e-5 -0.9950342 -0.09945571 3.99555e-6 -0.995042 1.24074e-4 0.9822869 0.1873833 0 0.9824694 0.1864241 0.1439538 1.63681e-4 -0.9895844 0.1435897 0 -0.9896374 0.1434589 5.63777e-5 -0.9896563 2.03673e-4 0.9507623 -0.3099211 0 0.9451236 -0.3267133 2.04656e-6 0.8970543 -0.4419205 -1.04442e-4 0.9054754 -0.4243988 0.261385 2.87156e-4 -0.9652346 0.2499842 -2.76612e-4 -0.9682499 0.2499008 -2.91479e-4 -0.9682714 0.2501608 -1.4216e-4 -0.9682044 0.2498962 -2.94156e-4 -0.9682727 0.2498152 1.38786e-6 -0.9682936 0.2500314 -5.09383e-5 -0.9682377 0 -0.9993909 -0.03489941 0 -0.9993909 -0.03489959 0.001029491 -0.9993667 -0.03557026 0.02787828 -0.9990176 -0.0344479 0.02623295 -0.9990465 -0.0349003 0.02623045 -0.9990465 -0.03490191 0.02623063 -0.9990466 -0.03489965 -0.2320489 5.48203e-4 -0.972704 -0.236924 1.87682e-5 -0.9715282 -0.2369553 7.67109e-6 -0.9715206 -0.2369298 -5.78945e-6 -0.9715269 -0.2369186 -1.00124e-5 -0.9715296 -0.2369315 -6.61439e-6 -0.9715264 -0.2365532 -3.04724e-5 -0.9716185 0.06873291 -0.9970489 -0.03419661 0.0704503 -0.9968974 -0.03510653 0.05938917 -0.9976179 -0.03509438 0.05953639 -0.9976117 -0.03502058 -5.10383e-4 0.9510561 0.309018 -0.8913999 -0.4518722 0.03489965 -0.8913998 -0.4518722 0.03489965 -0.8913992 -0.4518736 0.03489965 -0.8913989 -0.451874 0.03489977 -0.960331 -0.2765743 0.03565287 -0.9625565 -0.2690063 0.03347873 -0.956891 -0.2883385 0.03493756 -0.99183 -0.1226947 0.03491979 -0.9906439 -0.1321216 0.03418624 -0.9887942 -0.1447613 0.03647285 -0.9993884 -0.002176761 0.03490442 -0.999405 0.004882931 0.03414452 -0.9994325 0.001571714 0.03365367 -0.9884298 0.1476131 0.03488588 -0.987784 0.1521528 0.03364956 -0.9466235 0.3207025 0.0324676 -0.9492581 0.3125561 0.03489953 -0.8922591 0.450174 0.0348851 -0.8902307 0.4542662 0.03363817 -0.815099 0.5782765 0.03478562 -0.7981007 0.6014345 0.03622156 -0.7886118 0.6140974 0.03124082 -0.8054938 0.5915738 0.03493434 -0.6645759 0.7464054 0.03489935 -0.6645768 0.7464046 0.03489965 -0.6481813 0.7609183 0.02940183 -0.6743552 0.7375799 0.03494215 -0.4889067 0.8715495 0.03703898 -0.5106609 0.8590736 0.03489935 -0.5162687 0.8556393 0.03671509 -0.4686431 0.882706 0.03469777 -0.3537082 0.9347044 0.034904 -0.355331 0.9340926 0.03479784 -0.356812 0.9335125 0.0352118 -0.2006578 0.9790392 0.03491204 -0.2070669 0.9777358 0.03400254 -0.2132306 0.9763778 0.0349155 -0.09062302 0.9952736 0.03489971 -0.09062385 0.9952735 0.03489959 -0.01015639 0.9993633 0.03420549 -0.01598238 0.9992632 0.03489482 0.05810326 0.9976638 0.03592985 0.05941385 0.9976211 0.0349586 0.05653637 0.9978193 0.03406578 0.05618673 0.9978179 0.03467595 0.05157071 0.9980267 0.03582084 0.05047553 0.9981251 0.03461897 0.04584687 0.9983152 0.03556561 0.04615169 0.9983226 0.0349583 0.03998398 0.9986499 0.03316062 0.03850352 0.9986031 0.03618711 0.03181761 0.9987933 0.037413 0.03335732 0.9988645 0.03401404 0.02769416 0.9991292 0.03120553 0.02087378 0.9990471 0.03833079 0.02085953 0.9990451 0.03839242 0.01654803 0.9993117 0.03320133 0.009009003 0.9992806 0.03683769 0.006013274 0.9994931 0.03126633 -0.01448506 0.9992498 0.03591853 -0.01557934 0.9992695 0.03489941 -0.03376567 0.9988203 0.03489857 -0.03433668 0.9988237 0.03423959 -0.05500966 0.9978795 0.03479498 -0.05480813 0.9978961 0.03463339 -0.1044391 0.9941613 0.02712798 0.00150907 0.9993637 0.0356369 -0.005012512 0.9994198 0.03368932 0.05826264 0.9976138 0.03704494 0.0938369 0.9950726 0.03202265 0.1441928 0.9888256 0.03784787 0.1871013 0.9818537 0.03092765 0.2435091 0.9693392 0.0329371 0.2355391 0.9713652 0.0311619 0.3130315 0.9493464 0.02743202 0.3430362 0.9386834 0.03463768 0.4022189 0.9147531 0.03803443 0.4379613 0.8985016 0.02974516 0.5089192 0.8598833 0.04002481 0.5336877 0.8450251 0.03331881 0.6289045 0.7766339 0.03632003 0.6286675 0.7768205 0.03643149 0.7052764 0.7084229 0.02687668 0.7386475 0.6731058 0.03644806 0.7714881 0.6353747 0.03324741 0.765461 0.6427616 0.03044843 0.8290296 0.5582431 0.03278303 0.8347206 0.5495613 0.03498321 0.8540945 0.519396 0.02739745 0.8750925 0.4826952 0.03490579 0.9047811 0.4245291 0.03385758 0.8992269 0.4364326 0.03029531 0.9366974 0.3483842 0.03502202 0.9449851 0.3256626 0.03077393 0.9544175 0.2966592 0.03287267 0.957862 0.2850756 0.03510785 0.9781588 0.2051191 0.03363978 0.9791848 0.200322 0.03268402 0.985364 0.166609 0.03604459 0.9949148 0.09456276 0.0346769 0.9965835 0.07703197 0.02979183 0.9986675 0.03743332 0.0355246 0.9994501 0.00817579 0.03213578 0.9971475 -0.06703698 0.03468197 0.9973481 -0.06348097 0.03559589 0.9825206 -0.1835628 0.03094881 0.9825957 -0.1831446 0.03104591 0.9724303 -0.2305709 0.03487807 0.9697868 -0.2417561 0.032673 0.939118 -0.3418179 0.03489911 0.9391175 -0.3418192 0.03490144 0.8983186 -0.4381245 0.03271985 0.9016998 -0.4309509 0.03491234 0.8382295 -0.5443627 0.03226035 0.8389366 -0.5432459 0.03270161 0.7485305 -0.6621813 0.03490024 0.7466489 -0.6643636 0.03371369 0.6432541 -0.7648571 0.03489732 0.6432578 -0.7648539 0.03490012 0.558848 -0.8285354 0.03490042 0.558852 -0.8285328 0.03489768 0.4691619 -0.8823872 0.03577846 0.4671272 -0.8835012 0.03489649 0.3122885 -0.9493463 0.03489279 0.308816 -0.9504226 0.0364626 0.2077771 -0.977518 0.03587955 0.2044692 -0.9782509 0.03489309 0.0648806 -0.9972813 0.03493773 0.0798223 -0.996271 0.03275001 0.09878224 -0.9944163 0.03712576 -0.07982003 -0.9962707 0.03276461 -0.09559339 -0.9948029 0.03505861 -0.06528365 -0.9972551 0.03493523 -0.1601489 -0.9864823 0.03471243 -0.1573727 -0.9870089 0.0323646 -0.147556 -0.9884312 0.03508961 -0.1020304 -0.9941951 0.03414589 -0.1021912 -0.9941866 0.03391247 -0.03475713 -0.9987863 0.0349 -0.03507691 -0.9987626 0.03525406 -5.16501e-4 -0.9993908 0.03489941 0 -0.9993332 0.03651499 0.02339875 -0.9992967 0.02930575 0.02623182 -0.9989666 0.03711891 0.0307641 -0.998971 0.03332513 0.03182142 -0.9988773 0.03509306 0.04317307 -0.9985168 0.03317338 0.04249835 -0.9985006 0.03450447 0.04993057 -0.998086 0.03649008 0.0548374 -0.9980099 0.03113126 0.05891072 -0.997612 0.03605288 0.06557488 -0.9973083 0.03280448 0.0701074 -0.9968492 0.03710561 0.07879436 -0.9962738 0.03507316 0.07731986 -0.9964511 0.03327119 0.09236025 -0.9951139 0.03489995 0.09250622 -0.9951125 0.03455162 0.03847235 -0.9984574 0.04003447 0.05199903 -0.9980399 0.034823 0.03906154 -0.9990184 0.02089422 0.05201804 -0.9980275 0.0351504 0.05283349 -0.9979933 0.03489977 0.05246359 -0.9980134 0.03488349 -0.02140253 -0.9993444 0.02920359 -0.04688316 -0.9980476 0.04126745 -0.1329421 -0.9906998 0.02898961 -0.12781 -0.9912883 0.03181755 -0.2164871 -0.9756616 0.03489941 -0.2017161 -0.9790579 0.02749949 -0.3019654 -0.9526799 0.03490012 -0.3019648 -0.9526802 0.03489959 -0.4125928 -0.9102469 0.03489935 -0.4125938 -0.9102464 0.03489965 -0.5371962 -0.842735 0.03489845 -0.5371967 -0.8427346 0.03489929 -0.6657471 -0.7453609 0.03489923 -0.665748 -0.7453601 0.03489881 -0.7924851 -0.608892 0.03490018 -0.7924853 -0.6088919 0.03489911 -0.8079444 -0.5886057 0.0277391 -0.7924546 -0.608868 0.03599357 -0.7865453 -0.61699 0.02588164 -0.7958023 -0.6045511 0.03488194 -0.7924842 -0.6088933 0.03489965 -0.7924849 -0.6088922 0.03489959 0.05215626 -0.9980401 -0.03457969 -0.03195953 -0.9989339 -0.03331148 -0.03507727 -0.9987751 -0.03489941 -0.09910118 -0.9944652 -0.03490024 -0.1027609 -0.9940516 -0.03607612 -0.1091195 -0.9934641 -0.03349864 -0.1581613 -0.9867818 -0.03531205 -0.1576761 -0.9868741 -0.03489959 -0.07981437 -0.9961987 -0.03489893 -0.07981598 -0.9961985 -0.03489977 0.07981467 -0.9961987 -0.03489947 0.07981634 -0.9961985 -0.03489965 0.2077867 -0.9775515 -0.03489887 0.207786 -0.9775516 -0.03489953 0.3088248 -0.9504786 -0.03489869 0.3088321 -0.9504762 -0.03489774 0.4691794 -0.8824132 -0.03489685 0.4691825 -0.8824116 -0.0348953 0.558858 -0.828529 -0.03489446 0.5588528 -0.8285322 -0.03490084 0.6432508 -0.7648597 -0.03489947 0.6432721 -0.7648421 -0.03489732 0.7485175 -0.6621965 -0.03489392 0.7485248 -0.6621883 -0.034891 0.8381544 -0.5443158 -0.03489661 0.8381608 -0.5443058 -0.03489476 0.8982468 -0.4381027 -0.03491103 0.898247 -0.4381026 -0.03490757 0.9391288 -0.3417869 -0.03491175 0.9391158 -0.3418242 -0.03489691 0.9696969 -0.2418038 -0.03491193 0.9629841 -0.2638567 -0.05514889 0.9850605 -0.166578 -0.04367673 0.9866808 -0.1588787 -0.03491079 0.9971396 -0.06704264 -0.03489774 0.9982854 -0.05409276 -0.02236527 0.9988502 0.01014178 -0.04685574 0.9963725 0.08248662 -0.02092641 0.9939892 0.1009861 -0.04227799 0.9775314 0.2089556 -0.02775102 0.9780392 0.2069065 -0.02508062 0.9526873 0.2997558 -0.0503323 0.942494 0.3333355 -0.02434206 0.9131371 0.405147 -0.04512923 0.9106608 0.411124 -0.04091727 0.8557162 0.5149804 -0.05044913 0.8689661 0.4936395 -0.03489935 0.8289777 0.5581922 -0.03489476 0.8289548 0.5582256 -0.0349006 0.7766878 0.6289183 -0.03490203 0.7821205 0.6218917 -0.03921943 0.7146918 0.6978963 -0.04643833 0.7309262 0.6815638 -0.03489625 0.6289383 0.7766717 -0.03489607 0.6289369 0.7766728 -0.03489959 0.5396951 0.8411372 -0.03489124 0.5391465 0.8414795 -0.03511971 0.4520645 0.8913705 -0.03311061 0.4477501 0.8934624 -0.03528428 0.3405634 0.9396373 -0.03314262 0.3313779 0.9427649 -0.03719067 0.2354621 0.9710419 -0.040439 0.2470178 0.9682933 -0.03728783 0.1444028 0.9886672 -0.04104924 0.1732268 0.984234 -0.03572118 0.1021368 0.9941846 -0.03413724 0.094944 0.9948409 -0.03573983 0.001513719 0.9993864 -0.0349974 0.006303906 0.9993985 -0.03410202 -0.05497729 0.9978816 -0.03478473 -0.05439746 0.9979282 -0.03435724 -0.03375089 0.9988191 -0.034949 -0.03470969 0.9987631 -0.03560227 -0.01458698 0.9992844 -0.03489917 -0.01448601 0.9992879 -0.03484159 0.01080161 0.9993655 -0.03393954 0.007967352 0.9993591 -0.03489935 0.008748471 0.9993443 -0.03513568 0.01893734 0.9992219 -0.03459948 0.02196872 0.9991465 -0.03498035 0.02050054 0.9991527 -0.03569048 0.02590501 0.9990389 -0.03535884 0.02684438 0.9990355 -0.03475105 0.02987062 0.9989443 -0.03489977 0.0310558 0.998926 -0.03438627 0.03020328 0.9989497 -0.03445619 0.03332763 0.9988616 -0.03412836 0.0342015 0.9987862 -0.03544741 0.03388404 0.9987894 -0.03565865 0.03606772 0.9987484 -0.03465467 0.03855305 0.9986678 -0.03429967 0.0418086 0.9985172 -0.03486514 0.04331088 0.9984196 -0.0358138 0.04546701 0.9983607 -0.03476756 0.05066525 0.9980949 -0.03520947 0.05087673 0.9980901 -0.03504091 0.05506366 0.9978865 -0.03450435 0.05646538 0.9977697 -0.0356009 0.05935955 0.9976343 -0.03467303 0.0600056 0.9975944 -0.03471159 0.05958682 0.9976105 -0.03496885 0.03699856 0.9986971 -0.03514665 0.02867937 0.9990388 -0.0331518 -0.08193844 0.9959749 -0.03633439 -0.08651578 0.9956393 -0.03489089 -0.2070589 0.9777059 -0.03489959 -0.2070605 0.9777055 -0.03489869 -0.3553301 0.9340893 -0.03489911 -0.3553298 0.9340893 -0.03489971 -0.5105117 0.8591623 -0.03490006 -0.5106636 0.8590779 -0.03475457 -0.6640711 0.7468233 -0.03556269 -0.6645771 0.7464043 -0.03489917 -0.7981376 0.6014636 -0.03489941 -0.7981387 0.6014623 -0.03489875 -0.8901907 0.4542496 -0.0348984 -0.8855879 0.4622936 -0.04493004 -0.949266 0.312532 -0.03490006 -0.9504225 0.3084318 -0.03958529 -0.9877398 0.1521585 -0.03490012 -0.9858603 0.1611765 -0.04584354 -0.9993909 0 -0.03489989 -0.998901 -0.009767055 -0.04584199 -0.9906194 -0.1321187 -0.03489989 -0.9906193 -0.1321196 -0.03489995 -0.9603573 -0.2765798 -0.03489392 -0.9603563 -0.2765827 -0.03489965 -0.8913998 -0.4518719 -0.03490459 -0.8914008 -0.4518702 -0.03489965 -0.7924852 -0.6088919 -0.03489983 -0.7924851 -0.6088921 -0.03489911 -0.6657473 -0.7453608 -0.03489923 -0.664798 -0.7461556 -0.03599452 -0.5368692 -0.8429433 -0.03490102 -0.5372021 -0.8427414 -0.03465485 -0.4125924 -0.910247 -0.03489965 -0.412594 -0.9102463 -0.03489941 -0.3019658 -0.9526798 -0.03489923 -0.3019645 -0.9526802 -0.03489893 -0.2238836 -0.9739906 -0.03490966 -0.2170118 -0.97547 -0.0369355 -0.1110566 -0.9930828 -0.03812092 -0.117143 -0.9924492 -0.036363 -0.02177876 -0.9992024 -0.03346914 -0.01707625 -0.9992486 -0.03479599 0.05159342 -0.9980552 -0.03498804 0.05121833 -0.9980776 -0.03489792 0.09250503 -0.9951004 -0.03489935 0.09235793 -0.995119 -0.03475987 0.09250521 -0.9951005 -0.03489965 0.07806181 -0.9963549 -0.03440254 0.07879441 -0.9962787 -0.03493458 1.92879e-4 0.8309137 -0.5564014 -3.38771e-5 0.8466385 -0.5321685 -2.60629e-4 0.3918517 -0.9200284 1.44494e-4 0.2489248 -0.9685228 6.96089e-6 0.263756 -0.9645895 0.2877886 -2.35028e-4 -0.9576939 0.2875625 -1.40339e-4 -0.957762 0.2866133 -0.00101602 -0.9580458 0.2871907 3.49899e-4 -0.9578734 0.2869261 2.24808e-5 -0.9579527 0.2868365 -6.09189e-6 -0.9579796 0.2871165 0.001269578 -0.9578949 0.2868376 -2.41386e-6 -0.9579793 0.2868368 6.01472e-6 -0.9579796 0.2868365 0 -0.9579796 0.2868288 8.25968e-4 -0.9579816 0.2871118 -0.00148034 -0.9578959 0.287035 1.21165e-5 -0.9579201 0.2867935 -1.54594e-4 -0.9579924 0.2868385 7.81626e-5 -0.957979 -1.86773e-4 0.770865 -0.6369986 0 0.6845573 -0.728959 1.84314e-4 0.7031093 -0.7110818 -1.71525e-4 0.5674763 -0.8233898 0 0.5877642 -0.8090323 2.61754e-4 0.4574168 -0.8892525 -0.2686831 -1.66443e-4 -0.9632286 -0.2678127 5.11954e-7 -0.9634711 -0.2694957 2.65917e-4 -0.9630016 -0.2678104 5.41672e-6 -0.9634717 -0.2678048 1.06335e-5 -0.9634732 -0.2678205 -1.00553e-6 -0.9634688 -0.2677828 1.83429e-5 -0.9634794 -0.2678136 1.43878e-6 -0.9634708 -0.2677716 -1.60112e-6 -0.9634824 -0.2677569 -1.374e-5 -0.9634865 -0.2678034 0 -0.9634736 -0.2677646 -3.25244e-4 -0.9634843 -0.2677662 4.8268e-6 -0.9634839 -0.2677694 3.29894e-4 -0.963483 -0.2678033 -7.19514e-6 -0.9634737 -0.2677632 1.22832e-5 -0.9634848 -0.267769 2.88641e-6 -0.9634832 -0.2677574 2.25841e-5 -0.9634864 -0.2677817 -1.44363e-5 -0.9634797 -0.2678157 4.56405e-6 -0.9634702 -0.2677965 -6.04731e-6 -0.9634755 -0.2677742 -3.37743e-5 -0.9634818 -0.2678686 -5.80603e-5 -0.9634556 -1.95783e-5 0.1282721 -0.9917391 0 0.1252235 -0.9921286 0.06933778 1.58056e-5 0.9975934 0.06954985 5.34451e-5 0.9975785 -0.06951248 -4.01239e-5 -0.9975812 -0.06959497 -7.16457e-5 -0.9975754 0.06948143 6.63058e-7 0.9975833 0.06936621 -4.71785e-7 0.9975913 0.0693618 1.17635e-5 0.9975917 0.06931573 3.10811e-5 0.9975948 0.06931853 3.74477e-5 0.9975946 0.06914293 8.42151e-5 0.9976068 0.06909382 1.48909e-4 0.9976102 0.06848341 2.78093e-4 0.9976523 0.06938803 0 0.9975898 0.06922692 1.35731e-5 0.997601 0.0693196 6.85214e-5 0.9975946 0.06949603 -1.21946e-4 0.9975823 -0.06943821 6.88598e-5 -0.9975863 0.06638371 0.002723574 0.9977905 0.06137406 -0.09559708 0.9935263 0.06332641 0.04058527 0.9971674 0.06701272 3.38862e-4 0.9977521 0.06459885 0.04709291 0.9967995 0.06697899 1.58714e-4 0.9977543 0.06699866 -2.76037e-5 0.9977531 0.06860142 -0.01357388 0.9975519 0.06735664 0.02483028 0.99742 0.06701493 6.67787e-5 0.997752 0.06563568 -0.006655931 0.9978215 0.06697112 6.04819e-4 0.9977548 0.06684815 -6.05035e-4 0.997763 0.06700271 8.08147e-5 0.9977528 0.06707638 -4.71726e-5 0.9977478 0.06703817 0 0.9977504 0.06705582 1.19459e-5 0.9977492 0.065939 6.29724e-4 0.9978235 0.05700689 2.24462e-4 0.9983738 0.05806726 4.04842e-5 0.9983127 0.05776339 -9.78583e-7 0.9983303 0.05783867 1.7628e-5 0.998326 0.05786103 8.05144e-6 0.9983248 0.05698412 2.16652e-4 0.9983751 0.05783236 2.33803e-5 0.9983263 0.0578109 1.42657e-4 0.9983276 0.05776566 3.9797e-7 0.9983302 0.05796891 -3.41812e-5 0.9983185 0.05795657 1.28741e-5 0.9983192 0.0580036 5.04169e-5 0.9983164 0.05804717 9.69219e-5 0.9983139 0.05803465 6.17168e-5 0.9983146 0.04764044 1.60133e-4 0.9988645 0.04829257 -1.22567e-4 0.9988332 0.03700494 -4.56352e-6 0.9993152 0.0371977 -9.15944e-5 0.9993079 0.0244624 5.13309e-5 0.9997008 0.02432698 -9.10588e-6 0.9997041 0.009527981 1.51206e-4 0.9999547 0.008757054 -2.57525e-4 0.9999617 -0.01402342 3.30089e-5 0.9999018 -0.01439487 -1.96275e-4 0.9998965 -0.01297247 -7.00409e-7 0.999916 -0.01234054 5.96334e-4 0.9999237 -0.0139963 0 0.9999021 -0.01373904 9.93719e-5 0.9999056 -0.01197344 1.58995e-4 0.9999284 -0.01355493 1.60802e-4 0.9999082 -0.01184815 5.77223e-5 0.9999299 -0.01197463 5.23821e-4 0.9999282 -0.01268738 8.15225e-4 0.9999192 -0.01229155 6.95812e-5 0.9999245 -0.01290315 -3.62056e-6 0.9999169 -0.01291632 -1.11411e-5 0.9999167 -0.01292294 -1.71563e-5 0.9999166 -0.01290631 7.51466e-6 0.9999168 -0.01226603 3.06065e-4 0.9999248 -0.0261718 9.0906e-6 0.9996575 -0.02617394 -5.2734e-7 0.9996574 -0.02617996 0 0.9996573 -0.02619683 -5.74493e-6 0.9996568 -0.02614271 1.97794e-5 0.9996583 -0.02670758 -5.05638e-4 0.9996432 -0.02673548 -4.7269e-4 0.9996424 -0.02683258 -4.10693e-4 0.9996399 -0.02697712 -3.71418e-4 0.999636 -0.02719843 -3.46096e-4 0.99963 -0.02786868 -3.27003e-4 0.9996116 -0.02617269 -7.27572e-5 0.9996575 -0.02617275 -1.32462e-5 0.9996575 -0.02616953 -8.35155e-6 0.9996575 -0.0261864 -6.84518e-6 0.9996571 -0.02617847 -6.52504e-7 0.9996573 -0.02618116 -3.02104e-6 0.9996573 -0.0261777 1.49477e-6 0.9996574 -0.02505123 -2.13051e-4 0.9996862 -0.02533876 -2.62818e-4 0.999679 -0.02552181 -3.13846e-4 0.9996743 -0.02562397 -3.59649e-4 0.9996716 -0.02567619 -4.00707e-4 0.9996703 -0.02525025 1.63065e-4 0.9996812 -0.02573806 -2.61393e-4 0.9996688 -0.02430874 -1.27007e-4 0.9997046 -0.03202122 -3.57678e-4 0.9994872 0.02620661 4.07659e-4 -0.9996565 0.02514725 0.1878376 -0.9818782 0.02624428 0.002031803 -0.9996535 0.02617985 -8.20488e-5 -0.9996573 0.02609193 -2.20651e-4 -0.9996595 0.02638989 4.54129e-4 -0.9996516 0.03144252 0.008195102 -0.999472 0.02624565 3.69242e-5 -0.9996556 0.02619016 5.82868e-5 -0.999657 0.02623176 -3.59833e-5 -0.999656 0.02616482 -1.97919e-5 -0.9996577 0.02590602 2.74946e-4 -0.9996644 0.02584308 7.97386e-4 -0.9996657 0.02634871 -9.55924e-5 -0.9996529 0.02623361 -9.23069e-6 -0.9996559 0.02622336 -3.02888e-5 -0.9996562 0.05810362 0.00581032 -0.9982937 0.02527636 -4.21273e-4 -0.9996805 0.02765375 -2.4005e-4 -0.9996176 0.02663469 -5.05723e-4 -0.9996452 0.02359199 0.004423499 -0.9997119 0.02618497 9.97144e-5 -0.9996572 0.02615535 6.65108e-5 -0.999658 0.02586632 0.001155853 -0.9996648 -0.02617883 -4.47779e-5 0.9996573 0 -7.73119e-7 1 0 0 1 -3.42358e-6 0 -1 -2.7324e-6 3.45817e-7 -1 0 5.0506e-7 -1 5.13279e-6 -6.11241e-6 -1 -3.39777e-6 0 -1 -2.51197e-6 -1.74088e-6 -1 4.49537e-6 0 -1 -7.28574e-7 -9.22293e-7 -1 6.58838e-7 0 -1 1.32516e-5 0 -1 -1.24884e-6 -3.44198e-7 -1 0 1.21825e-6 -1 0 -2.88161e-6 -1 2.3796e-6 0 -1 7.29463e-7 0 -1 0 0 -1 9.96559e-7 6.39736e-7 -1 0 0 -1 7.85275e-7 5.29734e-7 -1 0 4.72329e-7 -1 -0.9991136 0.03293412 0.02622187 -0.9991713 0.03210324 0.02502447 -0.6741027 -0.737811 0.03493475 -0.6657476 -0.7453606 0.03489851 -0.6494324 -0.7603037 0.01326537 -0.6499137 -0.7586523 0.04537665 0.06938034 -4.89053e-6 0.9975903 0.3080049 9.22187e-4 -0.9513844 0.3082755 9.83958e-4 -0.9512966 0.3088341 6.63399e-5 -0.9511159 0.3088511 5.21816e-5 -0.9511105 0.3088568 5.33236e-5 -0.9511086 0.3110552 -1.53995e-4 -0.950392 0.3203698 3.03129e-4 -0.9472925 0.3198338 -8.87391e-6 -0.9474737 0.3198093 -2.87417e-6 -0.9474819 0.3198169 0 -0.9474794 0.3198025 -2.87499e-6 -0.9474843 0.3182945 -0.001274466 -0.9479911 0.3198238 3.07281e-6 -0.9474771 0.3189426 -0.002377748 -0.9477711 0.3155076 1.0228e-4 -0.9489231 0.3231461 -7.4521e-5 -0.9463492 0.3232468 0 -0.9463147 0.3232029 -5.32469e-5 -0.9463297 0.3232235 -8.17267e-5 -0.9463227 0.3233288 -9.24105e-6 -0.9462867 0.3220105 -1.88936e-5 -0.9467362 0.3223007 1.48198e-4 -0.9466375 0.3208993 -4.48833e-5 -0.9471133 0.3210762 2.12302e-5 -0.9470535 0.3195222 9.70977e-5 -0.9475788 0.31954 1.0725e-4 -0.9475728 0.3172989 -1.22786e-4 -0.9483257 0.3175625 2.0678e-4 -0.9482374 0.3172274 8.23441e-5 -0.9483496 0.3147025 -1.62284e-4 -0.9491904 0.3150619 5.63673e-5 -0.9490712 0.3150136 4.38804e-5 -0.9490872 0.3151752 -4.572e-6 -0.9490336 0.3151842 -3.34704e-6 -0.9490305 0.3151646 6.3328e-6 -0.9490371 0.3159986 -8.59031e-5 -0.9487597 0.3147956 1.26743e-5 -0.9491595 0.3147674 1.6689e-5 -0.9491689 0.3150862 2.92162e-6 -0.9490631 0.3132447 -2.37218e-5 -0.9496725 0.3122751 -6.00564e-6 -0.9499918 0.3117788 -2.44224e-5 -0.9501547 0.3098653 1.9415e-5 -0.9507805 0.3100183 5.81833e-6 -0.9507306 0.3101555 -1.0413e-5 -0.9506859 0.3099345 7.1638e-6 -0.950758 0.3091059 2.86464e-5 -0.9510277 0.3072772 -1.7476e-5 -0.9516201 0.307227 -1.50562e-5 -0.9516363 0.317156 1.81695e-6 -0.9483734 0.3176493 -4.10067e-5 -0.9482083 0.3185273 7.86876e-5 -0.9479138 0.3193714 1.00978e-5 -0.9476298 0.319604 -1.34609e-4 -0.9475513 0.3209137 5.63628e-5 -0.9471085 0.3213192 -6.51718e-5 -0.9469709 0.3220342 5.49675e-5 -0.9467281 0.3225108 -1.24422e-4 -0.9465658 0.3231348 6.36442e-5 -0.946353 0.3232038 4.78183e-5 -0.9463295 0.3232534 -1.59589e-5 -0.9463125 0.3234111 6.55163e-5 -0.9462587 0.323192 2.95574e-6 -0.9463335 0.3232805 1.19907e-4 -0.9463032 0.320301 -2.59538e-4 -0.9473158 0.3198689 0 -0.9474619 0.3198087 5.74485e-6 -0.9474822 0.3198122 -3.8024e-6 -0.947481 0.3198036 2.94331e-6 -0.9474838 0.3198332 -4.94169e-5 -0.9474739 0.3198451 -2.96025e-5 -0.9474699 0.3198279 -4.95335e-5 -0.9474757 0.3157496 -9.41178e-4 -0.9488422 0.3073828 6.5884e-4 -0.9515857 0.3087673 1.43621e-5 -0.9511377 0.3087791 1.95717e-5 -0.9511338 0.3087548 1.33908e-5 -0.9511417 0.311083 2.63089e-4 -0.9503828 0.3087967 3.99391e-5 -0.9511281 0.2570577 -4.20257e-4 -0.966396 0.249817 -8.63114e-7 -0.9682931 0.2497922 3.29256e-6 -0.9682995 0.2498007 -7.50065e-5 -0.9682974 0.2498814 -2.84432e-5 -0.9682765 0.2500138 -3.41338e-6 -0.9682424 0.199716 -1.17946e-5 -0.9798539 0.1990794 -2.08144e-5 -0.9799835 0.1992954 1.70943e-4 -0.9799395 0.1991884 2.02879e-5 -0.9799613 0.1439538 -9.6729e-5 -0.9895845 0.1435259 -3.71242e-6 -0.9896466 0.1436402 4.74199e-5 -0.9896301 0.09209352 -9.33179e-6 -0.9957504 0.08671933 -0.001104116 -0.9962322 0.09209853 5.58854e-6 -0.9957499 0.0921331 -1.60482e-5 -0.9957467 0.09213835 2.89185e-6 -0.9957463 0.09211641 -7.19893e-6 -0.9957484 0.04433548 -2.03846e-5 -0.9990168 0.04434072 -3.737e-6 -0.9990165 0.04433679 0 -0.9990167 0 1.48931e-5 -1 6.26676e-6 -1.44386e-5 -1 0 1.35137e-5 -1 9.76139e-7 -6.69512e-7 -1 -4.41632e-7 6.78338e-7 -1 -1.80019e-4 0.00537306 -0.9999856 0 -5.15047e-7 -1 -8.05171e-6 9.27602e-5 -1 0 -3.30605e-5 -1 0 4.96711e-6 -1 0 4.96703e-6 -1 -9.11631e-7 0 -1 0 0 -1 1.42091e-6 6.73673e-5 -1 -2.35924e-7 2.77054e-6 -1 0 6.70763e-5 -1 2.35922e-7 2.77051e-6 -1 0 5.58573e-7 -1 0 -3.30525e-7 -1 -9.19902e-6 1.04331e-5 -1 6.61861e-5 1.54219e-5 -1 0 -1.28299e-5 -1 6.2084e-6 1.43042e-5 -1 3.41066e-6 0 -1 4.43264e-7 6.80845e-7 -1 4.89694e-6 -4.80085e-7 -1 -4.14198e-5 -9.63622e-6 -1 0 -3.07949e-5 -1 1 -6.26764e-6 -1.46509e-5 -0.01360958 -2.57213e-5 -0.9999074 -0.01361507 0 -0.9999074 -0.01361012 3.09273e-7 -0.9999074 -0.0612502 -7.21166e-4 -0.9981223 -0.06199681 -9.07448e-7 -0.9980764 -0.0619809 -1.8651e-6 -0.9980774 -0.06198096 -5.09195e-6 -0.9980774 -0.06197726 -3.3641e-6 -0.9980776 -0.09949296 2.11887e-5 -0.9950383 -0.09944069 5.09549e-5 -0.9950435 -0.1433823 -1.2646e-4 -0.9896674 -0.1436376 -3.05978e-5 -0.9896304 -0.1437359 5.32225e-5 -0.9896161 -0.1908065 -4.56853e-5 -0.9816277 -0.1909366 -7.53492e-6 -0.9816024 -0.1902976 3.02165e-4 -0.9817264 -0.1910007 3.02235e-5 -0.98159 -0.2304525 -7.76185e-4 -0.9730833 -0.2369252 -1.95941e-5 -0.9715279 -0.2369215 -2.211e-5 -0.9715289 -0.2369123 -2.54479e-5 -0.9715311 -0.2369495 6.03309e-7 -0.971522 -0.2369366 2.51509e-6 -0.9715252 -0.2363521 2.90285e-5 -0.9716675 -0.2802661 4.86419e-4 -0.9599223 -0.2794367 1.8109e-4 -0.9601641 -0.2795704 1.30372e-6 -0.9601253 -0.2793041 6.50831e-5 -0.9602027 -0.2795663 7.61095e-7 -0.9601265 -0.279556 1.22099e-6 -0.9601294 -0.2795639 -9.18463e-7 -0.9601271 -0.2795693 -4.80384e-6 -0.9601255 -0.2790374 4.55881e-5 -0.9602802 -0.277348 -0.001142978 -0.9607689 -0.2680068 1.50351e-4 -0.9634171 -0.2682018 -4.63075e-6 -0.9633628 -0.2679382 1.05389e-4 -0.9634361 -0.268216 -3.94789e-6 -0.9633589 -0.2682001 -3.42e-6 -0.9633633 -0.2682123 -2.08041e-6 -0.9633599 -0.2682059 2.44545e-6 -0.9633616 -0.2682076 -1.19828e-6 -0.9633612 -0.2668474 -0.002299606 -0.9637361 -0.2644583 -2.81885e-4 -0.9643971 -0.266156 -7.90133e-5 -0.96393 -0.2379291 0.001335918 -0.9712816 -0.2376265 -0.002175331 -0.9713542 -0.2380704 -3.63087e-4 -0.9712479 -0.2384987 -1.94863e-6 -0.9711428 -0.2385101 -1.03661e-6 -0.97114 -0.2385089 -1.39948e-6 -0.9711404 -0.2385134 4.18376e-6 -0.9711393 -0.2385389 -1.41409e-5 -0.971133 -0.2385345 9.34634e-6 -0.971134 -0.2385333 -1.5135e-5 -0.9711344 -0.2385522 -7.83669e-6 -0.9711297 -0.2385761 2.9991e-6 -0.9711238 -0.2386977 7.95204e-5 -0.971094 -0.2387018 6.51191e-5 -0.971093 -0.2387725 4.41722e-5 -0.9710756 -0.2389077 1.47704e-5 -0.9710423 -0.2387654 3.60874e-5 -0.9710773 -0.2385067 6.90004e-7 -0.9711409 -0.2385128 -5.00986e-6 -0.9711394 -0.2387296 -8.57615e-5 -0.9710862 -0.2381029 3.98729e-4 -0.9712399 -0.2385039 3.15229e-6 -0.9711415 -0.2385058 2.17519e-6 -0.9711412 -0.2195119 -2.42639e-4 -0.9756098 -0.2159227 1.35375e-5 -0.9764105 -0.2160148 0 -0.9763902 -0.2162569 -5.62911e-5 -0.9763365 -0.2712088 0.001830279 -0.9625189 -0.268203 3.3562e-7 -0.9633624 -0.2679002 7.60133e-5 -0.9634467 -0.2682026 -1.66755e-6 -0.9633626 -0.2682059 -1.62751e-6 -0.9633617 -0.268217 4.47069e-6 -0.9633586 -0.2682103 4.30076e-6 -0.9633604 -0.2682027 -9.66027e-7 -0.9633626 -0.268208 -1.3403e-6 -0.9633611 -0.2682029 -7.5472e-6 -0.9633625 -0.265083 -0.001248419 -0.9642249 -0.2662629 0.003287196 -0.9638949 -0.263934 9.83227e-4 -0.9645403 -0.2799097 -1.22752e-4 -0.9600265 -0.2795528 5.4021e-6 -0.9601304 -0.2795662 -7.25016e-6 -0.9601265 -0.2795638 -2.87916e-6 -0.9601272 -0.2795639 -4.17504e-6 -0.9601272 -0.2795662 -5.54297e-6 -0.9601265 -0.2806282 -4.31997e-4 -0.9598165 -0.2795651 -2.95328e-6 -0.9601268 -0.2790868 -0.001044392 -0.9602653 0.9507524 0.3088443 0.02617716 0.9507296 0.3089154 0.02616488 0 -0.1252226 -0.9921287 -1.93808e-5 -0.1282292 -0.9917446 3.8418e-6 -0.248462 -0.9686416 -1.00885e-4 -0.264564 -0.9643681 0.950758 -0.3088266 0.02617728 0.9507247 -0.3089306 0.02616447 0.9819479 -0.1873317 0.02617567 0.9819501 -0.1873208 0.02617698 0.9976845 -0.06277263 0.02617621 0.997686 -0.0627498 0.02617573 0.9976845 0.06277263 0.02617621 0.997686 0.0627498 0.02617573 0.981948 0.1873317 0.02617567 0.9819501 0.1873208 0.02617698 -0.7068646 0.7068646 0.02617275 -0.7068821 0.7068468 0.02617692 -0.7768792 0.6291055 0.02617663 -0.7768794 0.6291052 0.02617698 -0.8383833 0.5444524 0.02617704 -0.8383837 0.5444516 0.02617704 -0.8907011 0.4538353 0.02617698 -0.8907018 0.453834 0.02617698 -0.9332594 0.3582481 0.02617686 -0.9332607 0.3582445 0.02617704 -0.9655954 0.2587285 0.02617698 -0.9655947 0.258731 0.02617681 -0.9873502 0.1563796 0.02617686 -0.9873497 0.1563822 0.02617686 -0.9982874 0.05231815 0.02617686 -0.9982876 0.05231571 0.02617686 -0.9982876 -0.05231571 0.02617686 -0.9982874 -0.05231815 0.02617686 -0.9873497 -0.1563822 0.02617686 -0.9873502 -0.1563796 0.02617686 -0.9655947 -0.2587311 0.02617681 -0.9655954 -0.2587285 0.02617698 -0.9332609 -0.3582444 0.02617698 -0.9332594 -0.3582481 0.02617686 -0.8907022 -0.453833 0.02617698 -0.8907011 -0.4538353 0.02617698 -0.8383837 -0.5444515 0.02617704 -0.8383833 -0.5444524 0.02617704 -0.7768794 -0.6291051 0.02617698 -0.7768792 -0.6291055 0.02617663 -0.7069095 -0.7068195 0.02617692 -0.7068644 -0.7068651 0.02616661 -0.9333732 -0.3573346 0.03356462 -0.9330108 -0.3581519 0.03490144 -0.9330115 -0.3581505 0.03489995 -0.8381609 -0.5443054 0.03489863 -0.8368104 -0.5466075 0.03112268 -0.8381587 -0.5443089 0.03489857 -0.8904633 -0.453715 0.03489756 -0.8904646 -0.4537123 0.03490078 -0.9629777 -0.2688562 0.01975727 -0.9649534 -0.2585578 0.04486525 -0.9879776 -0.1448214 0.05410176 -0.9873521 -0.1563844 0.02607238 -0.9981006 -0.05239355 0.03240662 -0.9981116 -0.05230915 0.03220313 -0.998062 0.05152106 0.03489714 -0.9980846 0.05230742 0.03303015 -0.9870867 0.1563389 0.03490191 -0.9870865 0.1563405 0.03489857 -0.9653371 0.2586624 0.03490251 -0.9653376 0.2586603 0.03490227 -0.9330113 0.3581507 0.03490173 -0.9330111 0.3581512 0.03490239 -0.8904631 0.4537154 0.0348975 -0.8904647 0.453712 0.03490114 -0.8373183 0.5456011 0.03489345 -0.8382325 0.544355 0.03231203 -0.7892313 0.6138442 0.01758897 -0.7762938 0.6286278 0.04685068 -0.7103855 0.7034022 0.0240395 -0.7067647 0.7067628 0.03114598 -0.6227594 0.7819347 0.02736788 -0.6487127 0.7607725 0.01992732 -0.628937 0.7766726 0.03489923 -0.5390098 0.841576 0.03490656 -0.5441361 0.8378982 0.0429278 -0.4864763 0.8710504 0.06791239 -0.4537185 0.8904616 0.03489857 -0.4537137 0.890464 0.03489887 -0.3570354 0.9335379 0.03213644 -0.3581624 0.9330412 0.03396964 -0.2553926 0.9663375 0.03108865 -0.2586617 0.9653379 0.03488552 -0.1591187 0.9866427 0.0348941 -0.1563559 0.9871845 0.03193295 -0.05230402 0.9980213 0.03489983 -0.05230331 0.9980212 0.0349006 0.06090801 0.997781 0.02689474 0.05230337 0.9980211 0.03490126 0.1592677 0.9866182 0.03490483 0.1563277 0.9870061 0.03715747 1.19867e-6 0 -1 1.70372e-6 0 -1 2.9997e-7 0 -1 -0.01823657 0.002888023 -0.9998295 -4.24804e-7 0 -1 4.25306e-7 0 -1 4.25733e-7 0 -1 -4.24008e-7 0 -1 -4.23205e-7 0 -1 8.51858e-7 0 -1 -2.10698e-7 0 -1 4.2598e-7 0 -1 -1.26614e-6 0 -1 5.99336e-7 0 -1 -8.51738e-7 0 -1 -0.01853662 -0.002935647 -0.9998239 1.87141e-7 0 -1 7.48482e-7 0 1 1.83645e-6 0 1 -2.0237e-6 0 1 -1.93076e-7 0 1 1.15663e-6 0 1 -4.04736e-6 0 1 0.1593158 -0.9866104 0.03490513 0.1563273 -0.9870049 0.03719139 0.0598123 -0.9978537 0.02665448 0.05230337 -0.9980204 0.03492212 -0.0644567 -0.9964785 0.05362743 -0.05229038 -0.9977722 0.0414319 -0.1630321 -0.9857203 0.04214274 -0.1563403 -0.9870865 0.03490012 -0.2605994 -0.9648161 0.03489762 -0.2586855 -0.965428 0.03210628 -0.3019759 -0.9527179 0.03375422 -0.30061 -0.9531085 0.03489947 -0.2164865 -0.9756618 0.03489655 -0.2164869 -0.9756615 0.03490179 -0.1209935 -0.99204 0.03488755 -0.1277684 -0.9909669 0.04074227 -0.0647158 -0.9966529 0.04994922 -0.04689598 -0.9984183 0.03101259 -0.01216536 -0.9988844 0.04563003 0.9382667 0.324454 0.1199388 0.9386444 0.3225399 0.1221266 0.9727146 0.1978975 0.1210902 0.9727391 0.1978288 0.1210063 0.9900413 0.06986117 0.1222192 0.9904609 0.06784009 0.1199375 -1.16097e-4 -0.999637 0.02694743 -4.54181e-4 -0.9996344 0.02703881 -9.89757e-4 -0.9996335 0.02705782 -0.001555502 -0.9996357 0.02694565 -0.002191424 -0.9996406 0.0267201 -0.01682263 -0.9992508 0.03485536 -0.002562105 -0.9996458 0.02649104 0.009567141 -0.9999164 0.008703291 7.80648e-4 -0.9997384 0.02286279 7.98682e-5 -0.9996567 0.02620118 4.38438e-5 -0.9996564 0.02621173 1.99638e-5 -0.9996564 0.02621275 5.61265e-6 -0.9996564 0.02621048 7.92183e-4 -0.999648 0.02651929 0.005347609 -0.9995457 0.02966308 5.11782e-4 -0.9996989 0.02453279 -0.00284177 -0.9998105 0.01926022 -7.77966e-5 -0.9996916 0.02483338 9.81272e-5 -0.999657 0.02618896 -0.99002 -0.06836771 0.1232327 -0.9901365 -0.07049763 0.1210786 -0.9725897 -0.1978458 0.1221733 -0.9725878 -0.1978768 0.1221389 -0.9380477 -0.3238529 0.1232314 -0.9389688 -0.3219822 0.1210996 -0.382137 0.9235158 0.03301638 -0.3917145 0.9198412 0.02125984 -0.3913511 0.9198721 0.02607625 -0.3945177 0.9187479 0.01607149 -0.3912023 0.9199382 0.02597177 -0.3889237 0.9210787 0.0187776 -0.3871361 0.9218955 0.0153132 -0.3906522 0.9201923 0.0252422 -0.3909437 0.9200506 0.02588289 -0.399105 0.9163928 0.03065186 -0.3907564 0.9201304 0.02587503 -0.3895576 0.9206249 0.02635973 -0.390638 0.92018 0.02589994 -0.3929456 0.9191802 0.02649104 -0.3906926 0.9201267 0.02694517 -0.3926109 0.9193165 0.02672004 -0.3920108 0.9195659 0.0269463 -0.3910115 0.9199887 0.02703648 -0.3915022 0.9197794 0.02705615 0.961317 -0.2612925 0.08715522 0.9613546 -0.2611694 0.08710962 0.9877864 -0.1291601 0.08715468 0.987788 -0.1291469 0.08715599 0.9961948 0 0.08715474 0.9961948 0 0.0871548 0.9867545 0.136847 0.08711147 0.9867378 0.1369411 0.0871542 0.226334 -0.973967 0.01270329 0.208652 -0.9776841 0.024459 0.1881896 -0.981591 0.03261524 0.2114483 -0.9771391 0.02211219 0.2078467 -0.9778214 0.02579367 0.2082291 -0.9777292 0.0261988 0.2141337 -0.9761381 0.03607106 0.1993127 -0.9795393 0.02788233 0.20147 -0.979289 0.02007591 0.2041264 -0.9786977 0.02198517 0.2076641 -0.9779075 0.02393019 0.2413997 -0.9696688 0.03832399 0.2094079 -0.9775185 0.02461427 0.2067356 -0.9780481 0.02612406 0.2071087 -0.9778259 0.03102582 -0.9801319 -0.1564831 0.1218793 -0.9799944 -0.1577095 0.1214039 -0.9912713 -0.05029368 0.1218684 -0.9912708 -0.05029666 0.1218714 -0.9906951 0.06059062 0.1218684 -0.9906947 0.060597 0.1218693 -0.9778825 0.1699837 0.1218673 -0.9778825 0.1699817 0.1218694 -0.9543046 0.2730627 0.1214057 -0.9545616 0.2719535 0.1218746 0.3157503 0.9486606 0.01857358 0.3256909 0.9451364 0.02535355 0.3155562 0.948727 0.01847779 0.3209525 0.9468584 0.02118086 0.3254593 0.9451985 0.02600157 0.3287565 0.9441509 0.02232557 0.2594361 0.9633781 0.06779074 0.3368804 0.9411529 0.02725791 0.3264456 0.9448984 0.02450191 0.3399624 0.9403292 0.0143764 0.3121656 0.9495339 0.03062838 0.3254594 0.9451891 0.02634185 0.3520423 0.9348389 0.04628652 0.3183537 0.9475663 0.02773195 0.3247537 0.9453795 0.02815765 -0.246842 -0.9684272 0.03489875 -0.2485523 -0.968031 0.03373277 -0.3678989 -0.9292107 0.03489851 -0.3678991 -0.9292104 0.03490418 -0.4814672 -0.8757692 0.03489708 -0.4814607 -0.8757727 0.03489953 -0.5874186 -0.8085306 0.03489822 -0.5874258 -0.8085253 0.03489649 -0.684127 -0.7285277 0.03489494 -0.6841356 -0.7285196 0.03489798 -0.7700356 -0.6370456 0.03490233 -0.7700546 -0.637023 0.03489476 -0.843815 -0.535498 0.03490191 -0.84381 -0.535506 0.03490251 -0.9042773 -0.4255171 0.03489887 -0.9042746 -0.4255226 0.03490179 -0.9504776 -0.3088271 0.03490221 -0.9504802 -0.3088196 0.03489893 -0.9816884 -0.1872699 0.03490006 -0.9816896 -0.1872631 0.03490263 -0.9974187 -0.0627523 0.03490239 -0.9974185 -0.06275707 0.03490018 -0.9974187 0.0627523 0.03490239 -0.9974184 0.06275701 0.03490012 -0.9816884 0.1872699 0.03490006 -0.9816896 0.187263 0.03490257 -0.9504776 0.3088271 0.03490221 -0.9504802 0.3088198 0.03489893 -0.9042773 0.4255171 0.03489887 -0.9042744 0.4255228 0.03490179 -0.843815 0.535498 0.03490191 -0.8438099 0.535506 0.03490263 -0.7700356 0.6370456 0.03490233 -0.7700546 0.637023 0.03489494 -0.684127 0.7285277 0.03489494 -0.6841354 0.7285197 0.03489816 -0.5874186 0.8085306 0.03489822 -0.587426 0.8085253 0.03489649 -0.4814672 0.8757692 0.03489708 -0.4814611 0.8757723 0.03489983 -0.3678989 0.9292107 0.03489851 -0.3678991 0.9292104 0.03490442 -0.2485368 0.9679934 0.03490257 -0.2485392 0.9679932 0.03489494 -0.1045461 0.9940244 0.03139561 -0.1252327 0.9915136 0.03489661 -0.1252549 0.9915113 0.03488099 0.3683463 0.9290333 0.03490018 0.3433296 0.9388663 0.02559667 0.3678987 0.9292021 0.03512877 -0.00500822 0.9995091 0.03092968 0 0.9993909 0.03489857 0.125253 0.9915109 0.03489744 0.1252574 0.9915103 0.03489899 0.2525892 0.9669443 0.03489154 0.2485655 0.9680963 0.03170007 0.5901603 0.806531 0.03490966 0.5810591 0.8131123 0.03491151 0.5873787 0.8084684 0.03694921 0.481464 0.8757708 0.03489989 0.4814671 0.8757691 0.03489971 0.7051538 0.7084162 0.03007906 0.6746193 0.737339 0.03492939 0.6839597 0.7283466 0.04135674 0.8540666 0.5194039 0.02810835 0.8350079 0.5496185 0.02610492 0.8438066 0.5354976 0.03511172 0.7714939 0.6353616 0.03336191 0.770139 0.6370989 0.03148281 0.9545387 0.2966883 0.02884459 0.945049 0.3256653 0.02871519 0.950457 0.3088021 0.03567582 0.9048154 0.4245496 0.03266018 0.9043666 0.4255811 0.03164988 0.9856238 0.1665655 0.02831619 0.9793078 0.2003202 0.02877557 0.9816404 0.1872757 0.03619313 0.998894 0.03750467 0.0283612 0.9966288 0.07705211 0.02817839 0.997352 0.0627321 0.03679347 0.3606863 -0.9320335 0.03491353 0.3898008 -0.9202361 0.03494071 0.3678343 -0.929039 0.03980624 0.9974679 -0.06348162 0.0320636 0.9974914 -0.06277602 0.0327121 0.9824875 -0.1830318 0.03489524 0.9818218 -0.1872872 0.03081381 0.9504785 -0.3088256 0.0348922 0.9504807 -0.3088176 0.03490459 0.8999269 -0.4353246 0.0249865 0.9042773 -0.4255175 0.03489279 0.8392344 -0.5432819 0.02303552 0.8439242 -0.5355758 0.03083276 0.7721471 -0.6344857 0.03488647 0.7701207 -0.6370866 0.03217047 0.6841411 -0.7285141 0.0349034 0.6841263 -0.7285285 0.03489369 0.5874136 -0.8085343 0.03489738 0.5874208 -0.8085289 0.03490221 0.481464 -0.8757708 0.03489989 0.481467 -0.8757693 0.03489947 0.09907287 -0.9947102 0.02713358 0.1420242 -0.9892467 0.03493148 0.1252331 -0.991315 0.04014217 0.2485442 -0.9679917 0.03490006 0.2485408 -0.9679927 0.03489601 0 -0.9994375 0.03353917 -5.93706e-4 -0.9994516 0.03310829 -0.1473175 -0.9887982 0.02399373 -0.09542089 -0.995057 0.02750384 -0.1252555 -0.9914956 0.03532224 -0.434494 -0.899652 0.04290878 -0.4125943 -0.9102461 0.03489887 -0.385932 -0.9225267 0.001109838 -0.3894239 -0.9199001 0.04618227 -0.5412666 -0.8397716 0.04259449 -0.5371778 -0.8427022 0.03596007 -0.9997105 -0.006664276 0.02312594 -0.9996246 -1.05832e-4 0.0274021 -0.9979066 -0.05927151 0.0258733 -0.9978299 -0.06101578 0.02475112 -0.9911201 -0.1303681 0.02617537 -0.991222 -0.1295445 0.02640485 -0.9233925 -0.3829635 0.02617782 -0.9233899 -0.3829698 0.02617669 -0.7501484 -0.6607511 0.02617871 -0.7501468 -0.6607529 0.02617985 -0.5585097 -0.8290849 0.02617859 -0.5585131 -0.8290824 0.02618086 -0.2739958 -0.9613746 0.02617859 -0.2740056 -0.9613719 0.02617698 0 -0.9996573 0.02617621 0 -0.9996574 0.02617573 0.275547 -0.9609312 0.02617865 0.2755572 -0.9609283 0.02617532 0.546506 -0.8370463 0.02616924 0.5444577 -0.8384014 0.0254724 0.7428271 -0.6688567 0.02895939 0.7690684 -0.6388043 0.02151483 0.7768799 -0.6291046 0.02617591 0.7428936 -0.6688976 0.02617609 0.7428936 -0.6688977 0.02617555 0.6817587 -0.7311087 0.02617734 0.6817606 -0.7311069 0.02617561 0.629109 -0.7768763 0.02617663 0.6291071 -0.7768778 0.02617752 0.5875836 -0.80874 0.02617764 0.5875837 -0.80874 0.02617669 0.5054576 -0.8624014 0.02786505 0.5082831 -0.8607925 0.02616727 0.4117624 -0.9109211 0.02597391 0.4142273 -0.9098446 0.02446472 -0.7060694 -0.7073608 0.03326719 -0.7067471 -0.7067458 0.03192424 -0.7871953 -0.6166244 0.009900391 -0.7766162 -0.6288906 0.03693139 0.9046116 0.4254305 0.02620989 0.9045189 0.4256295 0.02617603 0.8440362 0.5356472 0.02617609 0.8440319 0.5356537 0.02617722 0.7702552 0.6371985 0.02617764 0.7702549 0.6371988 0.02617883 0.684316 0.7287155 0.0261783 0.6843074 0.7287238 0.02617555 0.5874298 0.8088518 0.02617537 0.5875824 0.8087398 0.02620983 0.4814919 0.8760602 0.02615636 0.4815999 0.8760002 0.02617788 0.3679998 0.9294574 0.0261777 0.3679929 0.9294602 0.02617716 0.2486033 0.9682516 0.0261777 0.2486035 0.9682516 0.0261771 0.1252896 0.9917749 0.02617722 0.1252911 0.9917746 0.02617728 9.79569e-7 0.9996574 0.02617716 0 0.9996573 0.02617669 -0.1252844 0.9917755 0.02617686 -0.1252898 0.9917749 0.02617585 -0.2485894 0.9682551 0.02618169 -0.2486041 0.9682515 0.02617681 -0.3679981 0.9294581 0.02617663 -0.3679988 0.9294579 0.02617633 -0.4815876 0.876007 0.02617591 -0.4815916 0.8760049 0.02617484 -0.5875861 0.8087383 0.02617567 -0.5875774 0.8087447 0.02617532 -0.6843231 0.7287089 0.02617669 -0.6843104 0.7287208 0.02617824 -0.7702444 0.6372115 0.02617901 -0.7702611 0.6371914 0.02617347 -0.8440425 0.5356371 0.02617853 -0.8440339 0.535651 0.02617007 -0.9045213 0.4256241 0.02617883 -0.904516 0.4256357 0.02617424 -0.9507257 0.3089267 0.02617353 -0.9507324 0.3089059 0.02617466 -0.9819509 0.1873165 0.02617454 -0.9819494 0.1873232 0.02618396 -0.9976835 0.06278628 0.02618408 -0.9976869 0.06273853 0.02616852 -0.9976835 -0.06278628 0.02618408 -0.9976869 -0.06273853 0.02616852 -0.9819509 -0.1873163 0.02617454 -0.9819494 -0.1873232 0.02618396 -0.9507286 -0.3089178 0.026174 -0.9507324 -0.3089059 0.02617466 -0.904513 -0.4256416 0.02618432 -0.9045149 -0.425638 0.02617496 -0.8440433 -0.5356359 0.02617496 -0.8440341 -0.5356506 0.02617484 -0.7702446 -0.6372112 0.026178 -0.7702518 -0.6372027 0.02617514 -0.6843124 -0.7287191 0.02617615 -0.6843181 -0.7287136 0.02617943 -0.5875861 -0.8087383 0.0261752 -0.5875774 -0.8087447 0.02617532 -0.4815874 -0.8760071 0.02617561 -0.4815922 -0.8760045 0.02617478 -0.3679979 -0.9294582 0.02617675 -0.3679988 -0.9294579 0.02617633 -0.2485774 -0.9682581 0.02618521 -0.2486041 -0.9682515 0.02617681 -0.12529 -0.9917748 0.02617532 -0.1252787 -0.9917763 0.02617609 9.79569e-7 -0.9996574 0.02617716 0 -0.9996573 0.02617669 0.1252897 -0.9917749 0.0261774 0.1252911 -0.9917746 0.02617728 0.2486033 -0.9682516 0.0261777 0.2486035 -0.9682516 0.0261771 0.3679997 -0.9294574 0.02617764 0.3679929 -0.9294602 0.02617716 0.4814908 -0.8760608 0.02615529 0.4815999 -0.8760002 0.02617788 0.5874301 -0.8088515 0.02617561 0.5875808 -0.8087409 0.0262103 0.6843159 -0.7287157 0.02617835 0.6843074 -0.7287238 0.02617555 0.7702552 -0.6371985 0.0261777 0.7702549 -0.6371988 0.02617883 0.8440362 -0.5356472 0.02617609 0.8440319 -0.5356537 0.02617722 0.9046214 -0.4254093 0.02621346 0.9045189 -0.4256295 0.02617603 -2.02767e-4 -0.8323447 -0.5542584 -2.48319e-5 -0.8442853 -0.5358939 8.05385e-6 -0.8996664 -0.436578 -1.51685e-4 -0.9123068 -0.4095076 2.60641e-4 -0.3918713 -0.9200201 -2.61778e-4 -0.4573858 -0.8892683 2.29674e-4 -0.5816054 -0.8134711 1.58561e-4 -0.5874716 -0.8092449 -2.83903e-4 -0.7032814 -0.7109115 2.91528e-4 -0.7529133 -0.6581197 -5.51539e-4 -0.9983494 -0.05743068 0 -0.9978386 -0.06571459 5.41064e-5 -0.997986 -0.06343454 2.02142e-4 -0.9967038 -0.08112764 0 -0.9986613 0.05172753 6.92245e-4 -0.9982007 0.0599597 3.89397e-4 -0.9440514 -0.3297981 -2.6463e-4 -0.9769154 -0.2136267 0 -0.9822874 -0.1873807 1.26144e-4 -0.9822867 0.1873842 0 -0.9824733 0.1864036 -5.20126e-4 -0.9510565 0.3090167 -0.7148796 -0.6650235 0.2160806 -1 2.63117e-6 0 -1 5.17891e-5 1.49366e-4 -0.7071053 -0.7071083 0 -0.7071033 -0.7071104 3.53647e-6 0 -1 0 -0.7071074 -0.7071063 0 -0.7071068 -0.7071068 0 0 3.72045e-5 -1 1 -9.24027e-7 0 1 -3.00878e-6 0 1 -1.32449e-5 -6.44398e-5 0.7071024 -0.7071112 0 0.7071096 -0.707104 -1.12369e-6 0 -1 3.06301e-7 0.7071082 -0.7071055 0 0.7071082 -0.7071054 0 0.4207104 0.9071881 -0.003545403 0.1859287 0.9825484 0.005409181 0.01576131 0.9998428 -0.008135795 -0.9846242 -0.1746023 0.005409121 -0.2093423 0.9778277 0.005375325 -0.9512786 -0.3082836 -0.005508542 -0.8103948 -0.5858774 0.002859771 -0.4453581 0.8953365 -0.005352318 -0.8050851 -0.5931455 0.004047453 -0.8317781 0.5551065 0.001485466 -0.4917032 -0.8707629 0 -0.5123702 -0.8587612 -0.002437472 -0.9855983 0.1690968 0.001497745 -0.1859301 -0.9825599 0.002438902 -0.2093607 -0.9778386 0 -0.9938696 0.1104483 -0.004943549 0.2603605 -0.9654967 0.005354821 0.1859316 -0.9825598 -0.002438902 0.4917117 -0.8707415 -0.005375742 0.6397954 -0.7685266 0.005373299 0.8527351 -0.522338 0.002438008 0.8103905 -0.5858656 -0.005355417 0.9898454 -0.1421199 -0.002859711 0.9885211 -0.1510287 -0.004050374 0.9846224 0.1746047 0.005670726 0.942497 0.3341069 -0.00848788 0.8138616 0.5810019 0.008134663 0.7030161 0.7111534 -0.005407392 0.5075698 0.8616034 0.003546059 -0.003973722 -0.9439523 0.3300582 4.46693e-4 -0.9518472 0.3065728 -1.11177e-4 -0.9822875 0.1873801 0 -0.9826393 0.1855266 0 -0.9989944 0.0448364 -5.71183e-4 -0.9984622 0.05543643 -0.1563788 -0.9873503 0.02617627 -0.1563816 -0.9873498 0.02617704 -0.05235201 -0.9982856 0.02617728 -0.05231755 -0.9982876 0.02616924 -0.6292762 -0.7767397 0.02621448 -0.6291049 -0.7768796 0.02617698 -0.5444529 -0.838383 0.02617692 -0.5444529 -0.8383828 0.02617698 -0.453835 -0.8907012 0.0261771 -0.4538345 -0.8907014 0.02617704 -0.3582449 -0.9332606 0.02617686 -0.3582459 -0.9332603 0.0261771 -0.2587312 -0.9655947 0.02617734 -0.2587291 -0.9655953 0.02617603 0.5444515 -0.8383839 0.02617734 0.5444526 -0.8383831 0.02617669 0.6289815 -0.7769796 0.02617692 0.6291064 -0.7768805 0.0261141 0.05219745 -0.9982929 0.02620708 0.05231755 -0.9982874 0.02617704 0.1563805 -0.9873499 0.02617728 0.1563816 -0.9873499 0.02617657 0.2587307 -0.9655947 0.02617698 0.2587291 -0.9655953 0.02617681 0.3582449 -0.9332606 0.02617686 0.3582459 -0.9332603 0.02617722 0.4538349 -0.8907013 0.02617663 0.4538348 -0.8907014 0.0261774 0.7068645 0.7068645 0.02617633 0.7064063 0.7073122 0.02645182 0.6289813 0.7769796 0.02617663 0.6291068 0.7768801 0.02611452 0.7064067 -0.7073119 0.02645164 0.7068645 -0.7068645 0.02617633 0.7768808 -0.6291034 0.02617645 0.7768789 -0.6291057 0.02617681 0.8383833 -0.5444523 0.0261771 0.8383821 -0.5444541 0.02617728 0.8907016 -0.4538342 0.02617722 0.8907021 -0.4538332 0.02617716 0.9332596 -0.3582478 0.0261771 0.9332607 -0.358245 0.02617681 0.9655948 -0.2587307 0.02617675 0.9655948 -0.2587309 0.02617597 0.9873504 -0.1563788 0.02617597 0.9873498 -0.1563816 0.02617681 0.9982873 -0.05231833 0.02617675 0.9982875 -0.05231678 0.02617657 0.9982875 0.05231678 0.02617657 0.9982874 0.05231833 0.02617675 0.9873498 0.1563816 0.02617681 0.9873504 0.1563788 0.02617597 0.9655948 0.2587309 0.02617597 0.9655947 0.2587308 0.02617675 0.9332607 0.358245 0.02617681 0.93326 0.3582468 0.02617704 0.8907021 0.4538332 0.02617716 0.890702 0.4538336 0.02617722 0.8383821 0.5444541 0.02617728 0.8383833 0.5444522 0.0261771 0.7768789 0.6291057 0.02617681 0.7768802 0.6291041 0.02617645 0.05231755 0.9982874 0.02617704 0.05217361 0.998294 0.0262137 -0.05231761 0.9982877 0.02616751 -0.05235844 0.9982852 0.02617734 0.5444526 0.8383831 0.02617669 0.5444514 0.8383839 0.02617752 0.4538348 0.8907014 0.0261774 0.4538348 0.8907013 0.02617651 0.3582459 0.9332603 0.02617722 0.358245 0.9332606 0.02617686 0.2587291 0.9655953 0.02617681 0.2587308 0.9655947 0.02617686 0.1563816 0.9873499 0.02617657 0.1563805 0.9873499 0.0261774 -0.6291049 0.7768796 0.02617698 -0.6291754 0.7768219 0.02619218 -0.1563816 0.9873498 0.02617704 -0.1563788 0.9873503 0.02617639 -0.2587291 0.9655953 0.02617603 -0.2587312 0.9655947 0.02617716 -0.3582459 0.9332603 0.0261771 -0.358245 0.9332606 0.02617686 -0.4538345 0.8907014 0.02617704 -0.4538347 0.8907015 0.0261771 -0.5444529 0.8383828 0.02617698 -0.5444528 0.838383 0.02617698 -1.87087e-5 0 -1 -2.50747e-5 0 -1 1.87066e-5 0 -1 3.74142e-5 0 -1 5.74696e-6 0 -1 -4.73257e-6 0 -1 -1.87061e-5 0 -1 -2.3671e-7 0 -1 4.00158e-6 0 -1 -3.22255e-6 0 -1 2.15315e-6 0 -1 -7.51391e-6 0 -1 1.87077e-5 0 -1 6.26855e-6 0 -1 -1.87082e-5 0 -1 -1.97119e-7 0 -1 -1.14944e-5 0 -1 -9.46515e-6 0 -1 -3.75695e-6 0 -1 1.03531e-5 0 -1 -2.4622e-7 0 -1 3.15903e-6 0 -1 -1.25375e-5 0 -1 5.61205e-5 0 -1 -3.85731e-5 0 -1 1.9286e-5 0 -1 -1.92864e-5 0 -1 -4.82141e-6 0 -1 3.85731e-5 0 -1 3.28887e-6 0 -1 -9.6432e-6 0 -1 4.8216e-6 0 -1 0 0 -1 -2.57764e-7 0 -1 5.78755e-7 0 -1 4.73743e-7 0 -1 -4.05487e-7 0 -1 -6.45228e-6 0 -1 1.29047e-5 0 -1 5.2189e-6 0 -1 -1.68676e-6 0 -1 5.21891e-6 0 -1 -1.29047e-5 0 -1 -3.85728e-5 0 -1 -2.43071e-6 0 -1 -9.64302e-6 0 -1 3.1406e-7 0 -1 -1.92862e-5 0 -1 1.92864e-5 0 -1 5.21893e-6 0 -1 1.92862e-5 0 -1 -8.57187e-7 0 -1 6.48156e-7 0 1 0 0 1 2.69345e-7 0 1 1.51201e-7 0 1 1.71415e-6 0 1 -2.69345e-7 0 1 -4.54355e-7 0 1 -6.48156e-7 0 1 -4.29631e-7 0 1 -6.05253e-7 0 1 4.54355e-7 0 1 1.72222e-6 0 1 6.04451e-7 0 1 4.29105e-7 0 1 -2.16274e-7 0 1 -4.31305e-7 0 1 -1.21051e-6 0 1 1.07134e-6 0 1 -4.32282e-7 0 1 -8.61109e-7 0 1 -6.04451e-7 0 1 -6.04451e-7 0 1 8.61109e-7 0 1 8.59261e-7 0 1 4.32282e-7 0 1 -1.72222e-6 0 1 -1.07134e-6 0 1 -8.59261e-7 0 1 2.13963e-7 0 1 1.2089e-6 0 1 6.05806e-7 0 1 6.05253e-7 0 1 -2.13963e-7 0 1 2.16274e-7 0 1 -1.71415e-6 0 1 4.32415e-7 0 1 -4.29105e-7 0 1 -6.05806e-7 0 1 -1.51201e-7 0 1 -4.32415e-7 0 1 0 0 1 0.2586604 0.9653378 0.03489863 0.2586606 0.9653377 0.03489834 0 0.99936 -0.03577232 -0.1291957 0.9911065 0.03188306 0.2391769 0.9703806 -0.03400236 0.09690117 0.9948213 0.03067147 0.4644974 0.8850276 -0.03112035 0.9935815 -0.1131192 0 0.3180645 0.9476454 0.02834254 0.9926735 -0.1205323 -0.008449077 0.5229894 0.8519755 0.02490162 0.6628786 0.7482355 -0.02712184 0.9348997 -0.3545609 -0.01578652 0.9426974 -0.3335557 0.007893621 0.8227848 0.5679268 -0.02201086 0.7011889 0.7126852 0.02034705 0.8227849 -0.5679267 -0.02201098 0.8435287 -0.5368837 0.0146768 0.9348996 0.3545611 -0.01578658 0.8435287 0.5368837 0.0146768 0.6628785 -0.7482357 -0.02712172 0.9926735 0.1205322 -0.008449077 0.7011889 -0.7126852 0.02034705 0.9426974 0.3335557 0.007893621 0.9935815 0.1131192 0 0.4644976 -0.8850275 -0.03112059 0.5229894 -0.8519755 0.02490162 0.239177 -0.9703806 -0.03400236 0.3180645 -0.9476454 0.02834254 0 -0.99936 -0.03577232 0.09690117 -0.9948213 0.03067147 -0.2391566 -0.9702976 -0.03642684 -0.1291957 -0.9911065 0.03188306 -0.4644144 -0.8848685 -0.0364297 -0.3554943 -0.9339711 0.03635537 -0.662682 -0.7480144 -0.03642976 -0.5684809 -0.8218927 0.03635632 -0.7484952 -0.6621428 0.03635728 -0.822438 -0.5676872 -0.03643047 -0.8850944 -0.4639894 0.03635823 -0.9343956 -0.3543696 -0.03643131 -0.9703574 -0.2389239 0.03635865 -0.9920499 -0.1204568 -0.03643161 -0.9993388 0 0.03635895 -0.9920499 0.1204568 -0.03643161 -0.9703574 0.2389239 0.03635865 -0.9343956 0.3543696 -0.03643131 -0.8850944 0.4639894 0.03635823 -0.822438 0.5676872 -0.03643047 -0.662682 0.7480144 -0.03642976 -0.7484952 0.6621428 0.03635728 -0.4644144 0.8848685 -0.03642946 -0.5684809 0.8218927 0.03635632 -0.3554943 0.9339711 0.03635537 -0.2391566 0.9702976 -0.03642684 0.3581505 0.9330115 0.03489995 0.3581503 0.9330115 0.03489965 0.4537138 0.8904639 0.0349 0.4537127 0.8904644 0.03490108 0.5443074 0.8381597 0.03489995 0.5443072 0.8381598 0.03489834 0.6289373 0.7766724 0.03489995 0.6289365 0.7766731 0.03489869 0.7066767 0.7066754 0.03489995 0.7066754 0.7066767 0.03489905 0.7766723 0.6289373 0.0349006 0.7766728 0.6289368 0.03489828 0.8381602 0.5443064 0.03490066 0.8381589 0.5443086 0.03489923 0.8904644 0.4537131 0.03489857 0.8904647 0.4537123 0.03489983 0.9330115 0.35815 0.03489989 0.9330114 0.3581508 0.03489953 0.9653373 0.2586623 0.03489941 0.965338 0.2586596 0.03489929 0.9870862 0.1563422 0.03489941 0.9870865 0.1563404 0.03489911 0.9980213 0.05230236 0.03489935 0.9980213 0.05230331 0.03489941 0.9980213 -0.05230236 0.03489923 0.9980213 -0.05230337 0.03489947 0.9870865 -0.1563404 0.03489911 0.9870862 -0.1563421 0.03489947 0.9653373 -0.2586623 0.03489941 0.9653379 -0.2586598 0.03489935 0.9330115 -0.35815 0.03489989 0.9330114 -0.3581506 0.03489953 0.8904654 -0.4537109 0.03489965 0.8904637 -0.4537143 0.03489887 0.8381609 -0.5443055 0.03489899 0.8381584 -0.5443091 0.03490054 0.7766723 -0.6289373 0.0349006 0.7766727 -0.628937 0.03489845 0.7066767 -0.7066754 0.03489995 0.7066755 -0.7066767 0.03489869 0.6289373 -0.7766724 0.03489995 0.6289366 -0.776673 0.0348984 0.5443074 -0.8381597 0.03489726 0.5443072 -0.8381597 0.03490108 0.4537135 -0.890464 0.03489995 0.4537129 -0.8904643 0.03490108 0.3581505 -0.9330115 0.03489995 0.3581501 -0.9330115 0.03489899 0.2586604 -0.9653378 0.03489863 0.2586609 -0.9653376 0.03489875 -0.3843421 -0.9228307 0.02578413 -0.3880077 -0.919453 0.06368893 -0.3581511 -0.9330112 0.0349006 0.9048112 0.3104264 0.2914659 0.9041392 0.3106225 0.293336 0.9371337 0.1906642 0.2922801 0.93714 0.1906604 0.2922625 0.9541779 0.06778615 0.2914612 0.9536398 0.06734955 0.2933178 0.7411678 0.2542839 0.6212971 0.7403277 0.2535821 0.6225842 0.7673501 0.1561196 0.6219329 0.767351 0.1561197 0.6219318 0.7805569 0.05584436 0.6225854 0.7816012 0.05552577 0.6213024 0.4649014 0.1592422 0.870924 0.4642987 0.1588397 0.871319 0.4812088 0.09790277 0.8711218 0.4812099 0.09790486 0.871121 0.4894489 0.03520232 0.8713213 0.4901701 0.03506755 0.8709212 0.1538015 0.05261611 0.9866999 0.1536588 0.05253446 0.9867265 0.1592093 0.03239166 0.9867134 0.1592153 0.03239178 0.9867123 0.1619712 0.01168292 0.9867264 0.1621287 0.01166111 0.9867008 -0.1488878 -0.01073926 0.9887959 -0.1488415 -0.01074504 0.9888027 -0.1462549 -0.02975606 0.9887993 -0.1462604 -0.02975612 0.9887985 -0.1412072 -0.04826819 0.9888027 -0.1412513 -0.04829084 0.9887953 -0.4651105 -0.03352099 0.8846178 -0.4652996 -0.03359049 0.8845158 -0.4570453 -0.09298777 0.8845694 -0.4570544 -0.0929864 0.8845649 -0.4412368 -0.1508753 0.8846168 -0.4414247 -0.1508867 0.8845211 -0.7450063 -0.05347448 0.6649106 -0.7456071 -0.0537371 0.6642157 -0.7322295 -0.1489741 0.664565 -0.7322371 -0.1489774 0.664556 -0.7066752 -0.2418727 0.6649119 -0.7073388 -0.2418661 0.6642083 -0.8938708 -0.06395447 0.4437394 -0.894549 -0.0642088 0.442334 -0.8785067 -0.1787328 0.4430358 -0.8785071 -0.1787348 0.4430341 -0.8477994 -0.2903949 0.4437421 -0.8485268 -0.2904248 0.4423299 -0.9678615 -0.06891095 0.2418581 -0.9683188 -0.06927937 0.2399151 -0.9510641 -0.1935003 0.2409044 -0.9510707 -0.1934958 0.2408815 -0.9178465 -0.3147375 0.2418642 -0.9184066 -0.3145776 0.2399379 0.08958446 0.9956603 -0.02520287 0.05406486 0.9984824 -0.01049268 -0.01582223 0.9998555 0.006224393 0.02200788 0.9997525 0.003280043 -0.01981633 0.9998037 -4.82523e-5 0.01156049 0.999905 0.00751394 -0.09358447 0.9955406 -0.011877 0.006963431 0.9999601 0.00560528 -0.02243649 0.9997339 0.005365788 0.001210451 0.9999992 -6.07511e-4 0.01230466 0.9998849 0.008884608 -0.02407765 0.9996954 0.005423784 -0.02287113 0.9997242 0.005330681 0.4949861 -0.8681188 -0.0368601 0.4334737 -0.9011299 -0.008097529 0.3725026 -0.9279984 0.007801055 0.4159416 -0.9093819 0.004146516 0.3750602 -0.9270003 5.8235e-4 0.4065878 -0.9135687 0.008858561 0.2429634 -0.9695499 -0.03069001 0.3800202 -0.9249729 -0.003163874 0.3919704 -0.9199492 0.00727415 0.3916927 -0.9200941 0.001948654 0.4017854 -0.9156631 0.01138913 0.3510971 -0.9362576 0.01235282 0.4018927 -0.9156507 0.008143067 0.2271158 0.6595882 0.7164928 0.2274461 0.6573234 0.7184666 0.6526021 -0.1766534 0.7368203 0.6519637 -0.1771173 0.7372739 0.6698885 -0.08758485 0.7372777 0.669893 -0.08759331 0.7372726 0.6755884 0 0.7372791 0.6755893 0 0.7372782 0.6697849 0.0922923 0.7367974 0.6691851 0.09281378 0.7372767 0.1456428 -0.6801412 0.718468 0.145038 -0.6823561 0.7164874 -0.9757397 -0.2129417 -0.05087238 -0.1297969 0.9913803 -0.01782929 -0.2843018 0.9572676 0.0530219 -0.1487497 0.9881559 -0.03770393 -0.2069073 0.9783607 -5.32582e-5 -0.2518759 0.9660374 0.05770963 -0.1710516 0.9848268 0.02928835 -0.08914071 0.9949787 0.0455113 -0.2529298 0.9673023 -0.01878345 -0.08308857 0.9954447 0.04675579 0.9777501 0.203878 0.04938244 0.9405654 0.2159588 -0.2621044 -0.6579594 -0.1132256 0.7444927 -0.6542097 -0.1052935 0.7489479 -0.6617763 -0.03357708 0.7489492 -0.6617766 -0.03357779 0.7489488 -0.661392 0.04045248 0.7489488 -0.6613882 0.04045414 0.748952 -0.6528348 0.1134804 0.7489519 -0.6528322 0.1134827 0.7489538 -0.6370544 0.1822895 0.7489541 -0.6401543 0.1902933 0.7443057 0.9335056 -0.3215232 -0.1587139 -0.06937342 -0.9940648 0.08380192 -0.16259 -0.9619885 0.2194147 -0.3255754 -0.9455162 4.49646e-6 -0.3255701 -0.9455179 1.06144e-6 -0.3133634 -0.9100844 0.271201 -0.5572553 -0.8260987 0.08383035 -0.3255643 -0.94552 -3.43486e-6 -0.3255592 -0.9455217 -6.74422e-6 -0.4641147 -0.8581613 0.2194465 -0.9336477 0.3216794 -0.1575577 0 0 1 -0.4333845 -0.899398 0.05710631 -0.453767 -0.8905708 0.03129202 -0.5419589 -0.8397709 0.03264313 -0.5442576 -0.8380843 0.03739601 -0.648883 -0.7605183 0.02372634 -0.648498 -0.7585167 0.06405323 -0.6289365 -0.7766729 0.03489983 -0.7068234 -0.7064631 0.03620249 -0.7061313 -0.7072147 0.03501516 -0.6953381 -0.7059532 0.1346665 -0.7065178 -0.6919971 0.1482321 -4.32898e-5 0 -1 4.82085e-5 -1.97601e-6 -1 0 1.74194e-6 -1 2.2476e-5 -2.62019e-6 -1 -2.22346e-5 1.79068e-6 -1 0 2.58788e-6 -1 0 2.68468e-6 -1 2.38511e-5 -1.92087e-6 -1 1.66351e-4 4.00242e-5 -1 0 3.23767e-7 -1 -0.6501251 0 0.7598272 -0.3835175 0 0.9235337 -0.09642195 -0.9930449 0.06756275 -0.02402603 -0.9996948 0.005745947 -0.01663941 -0.9930431 0.1165695 -0.01937818 -0.999808 0.002902269 8.43892e-4 -0.9990169 0.04432439 -0.1699675 -0.9806262 -0.0973823 -0.01205664 -0.9999274 -1.23243e-4 0.004488289 -0.999989 -0.001397609 0.06121027 -0.9958154 0.06786137 -0.01043856 -0.9996556 -0.02408027 0.08197844 -0.9964066 0.02129298 0.00589174 -0.9999784 0.002958595 0.001634478 -0.9999987 3.44559e-4 -0.001181244 -0.9999981 -0.0016191 2.19212e-4 -0.999993 0.003745079 1.57785e-4 -0.999992 0.003998994 -0.008178412 -0.998933 0.04545485 0.06058335 -0.9959357 -0.06664788 -0.3328729 0.9402524 0.07156085 -0.3132573 0.9494899 0.01840716 -0.3846524 0.9191796 0.08456587 -0.4450462 0.8887143 0.1100953 -0.386239 0.9223645 0.007956266 -0.3895718 0.920995 0.001478016 -0.3897659 0.9209132 -0.001284837 -0.3913938 0.9201715 0.009772121 -0.2570639 0.9591169 -0.1183763 -0.389664 0.9209552 0.001894712 -0.3794031 0.9251654 -0.01106643 -0.4645952 0.8854426 0.01194781 -0.4269681 0.9042248 0.008705615 -0.392853 0.9196014 -2.32509e-4 -0.3926664 0.9196299 -0.009693086 -0.391884 0.9200134 0.001494705 -0.5330433 0.8399949 -0.1013594 -0.4060952 0.9137547 -0.0117954 -4.36185e-7 0 1 1.27221e-6 0 1 6.36579e-7 0 1 -5.88625e-7 0 1 -0.05276465 -0.9717918 0.2298626 -0.06276243 -0.9959604 -0.06421619 0.2240177 -0.9745749 -0.004470288 0.2168664 -0.9717428 0.09319335 0.1694493 -0.9818239 -0.08549171 0.332478 -0.8899107 0.3122777 0.1728708 -0.9844471 -0.03129786 0.19547 -0.9806917 -0.005951106 0.2050395 -0.9787513 -0.002233147 0.3311736 -0.9423127 0.04869246 0.3313018 -0.9422667 0.04871124 0.207911 -0.9781478 -1.85603e-6 0.2079108 -0.9781479 -1.06144e-6 0.2096362 -0.9777778 -0.001820325 0.2074312 -0.978248 -0.001808166 0.2092273 -0.9778671 2.20464e-4 0.3570454 -0.9307609 -0.07875901 0.2397729 -0.9705432 -0.02355772 -0.9464837 -0.1886816 0.2618545 -0.9442819 -0.2007281 0.2608445 -0.818681 -0.1739538 0.5472673 -0.6131864 -0.1302807 0.7791209 -0.3476653 -0.07382917 0.9347076 -0.04812002 -0.01022416 0.9987893 0.2561696 0.05440497 0.9650996 0.5352613 0.1141054 0.8369442 0.7620099 0.1623514 0.6268836 0.4640467 0.8582135 0.2193865 0.5573545 0.8260308 0.08384054 0.3255683 0.9455186 1.68611e-6 0.2923914 0.9559653 -0.02525532 0.3133652 0.9100663 0.2712599 0.1626057 0.961986 0.2194141 0.3278001 0.9446725 0.01186919 0.3427844 0.9393599 -0.0100972 0.339231 0.9407032 -3.143e-4 0.06944894 0.9940579 0.08382058 0.3255632 0.9455204 0 0.3255733 0.9455168 0 0.3257853 0.9454438 -3.13007e-4 0.3248313 0.9457617 -0.004413843 0.09579735 0.9919804 -0.08244907 0.3248328 0.9457443 0.007167577 0.3199343 0.947399 -0.008797109 0.3022928 0.9528744 -0.02548307 0.9339271 -0.3214066 0.1564543 -0.9337856 0.3218332 0.1564224 0.84235 -0.2904796 0.4539475 0.6685782 -0.2301591 0.7071281 0.4292193 -0.1478393 0.8910188 0.1479191 -0.05093401 0.9876871 -0.1479501 0.05092954 0.9876827 -0.4292582 0.1478325 0.8910011 -0.6685972 0.2301656 0.707108 -0.842467 0.2900622 0.4539971 -0.2393169 0.9709416 0 -0.2393178 0.9709414 0 0.9927103 -0.1205252 0 0.2393169 0.9709416 0 0.9927084 -0.1205406 0 0.2393178 0.9709414 0 0.9350159 -0.354606 0 0.4647217 0.8854569 0 0.4647178 0.885459 0 0.9350162 -0.3546053 0 0.6631319 0.7485026 0 0.8229796 -0.5680709 0 0.6631231 0.7485104 0 0.8229839 -0.5680648 0 0.8229802 0.56807 0 0.8229833 0.5680657 0 0.6631308 -0.7485036 0 0.6631242 -0.7485094 0 0.9350159 0.354606 0 0.9350162 0.3546053 0 0.4647209 -0.8854572 0 0.4647185 -0.8854585 0 0.9927102 0.1205254 0 0.9927085 0.1205404 0 0.239316 -0.9709418 0 0.2393187 -0.9709411 0 -0.239316 -0.9709418 0 -0.2393187 -0.9709411 0 -0.4647209 -0.8854572 0 -0.4647185 -0.8854585 0 -0.6631308 -0.7485036 0 -0.6631242 -0.7485094 0 -0.8229839 -0.5680648 0 -0.822976 -0.5680761 0 -0.9350162 -0.3546053 0 -0.9350159 -0.354606 0 -0.9927103 -0.1205252 0 -0.9927084 -0.1205406 0 -0.9927085 0.1205404 0 -0.9927102 0.1205254 0 -0.9350162 0.3546053 0 -0.9350159 0.354606 0 -0.8229767 0.5680752 0 -0.8229833 0.5680657 0 -0.6631319 0.7485026 0 -0.6631231 0.7485104 0 -0.4647217 0.8854569 0 -0.4647178 0.885459 0 -5.86074e-7 0 1 -3.3482e-6 0 1 2.27614e-6 0 1 3.34819e-6 0 1 -2.27614e-6 0 1 + + + + + + + + + + + + + + +

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

+
+
+
+ + + + 2.7116e-4 -0.005521237 -0.2583081 -0.003632009 -0.002338945 -0.2585064 0.004182159 -0.008455634 -0.2569551 -0.0072999 9.47908e-4 -0.2575646 0.003712058 8.48425e-4 -0.2162526 0.007619202 -0.002613306 -0.2173661 -0.01061969 0.004103362 -0.255522 -0.005987226 0.0152325 -0.2537461 0.01107394 -0.00590527 -0.2196968 -0.01472884 0.008753955 -0.2497201 -0.007765889 0.01792508 -0.2496902 0.01885896 -0.003284633 -0.2239336 -0.008956134 0.0206077 -0.2429885 0.01510244 -0.01047563 -0.2249531 0.02063763 -0.005977213 -0.2279896 -0.01665002 0.01242232 -0.2402259 0.02182781 -0.008659839 -0.2346913 -0.007979273 0.02141827 -0.2348492 0.01702368 -0.014144 -0.2344473 -0.01471364 0.01304739 -0.2300697 -0.006329119 0.02082836 -0.2299714 0.02085101 -0.009470343 -0.2428306 -0.003937065 0.0193752 -0.225609 -0.009363591 0.01048594 -0.2215787 -9.42194e-4 0.01714318 -0.2220155 0.0150873 -0.01476907 -0.2446034 0.0192008 -0.008880496 -0.2477084 -0.004538118 0.0073179 -0.2179016 -4.26947e-4 0.004231572 -0.2164341 0.01120477 -0.01286381 -0.2510812 0.007894158 -0.01095944 -0.2545036 0.02100384 0.0126484 -0.26236 0.02381044 0.00841856 -0.2606333 0.01819652 0.01719522 -0.2628013 0.01078557 0.01796108 -0.2612112 0.00837779 0.02209079 -0.2592088 0.0258916 0.01407611 -0.220865 0.02334368 0.01843404 -0.2201188 0.006397843 0.02576172 -0.2561258 0.02479541 0.007123231 -0.2223609 0.004994332 0.02878302 -0.2521396 0.02690094 0.003555595 -0.2254793 0.004265069 0.03098231 -0.2474803 0.0283913 6.24123e-4 -0.2294784 -2.93472e-5 0.02884775 -0.2416763 0.02919512 -0.001494765 -0.2341272 0.004996955 0.0324555 -0.2372755 0.02927535 -0.002675652 -0.239159 0.006424427 0.03165197 -0.2323422 0.02863407 -0.002846598 -0.2442869 0.008470535 0.02988082 -0.2279145 0.01103758 0.02726542 -0.2242479 0.02731388 -0.001991569 -0.2492177 0.01799142 0.02666175 -0.2221183 0.02064871 0.02269947 -0.2205528 0.02540093 -1.49174e-4 -0.2536682 0.02644473 0.004781246 -0.2577384 0.008943319 0.03514242 -0.24309 0.0237264 0.02545982 -0.2628991 0.02182972 0.02987098 -0.2609475 0.01953876 0.0358498 -0.2557666 0.03423088 0.01258152 -0.2235805 0.03576719 0.008672773 -0.226618 0.01848828 0.04019784 -0.2464236 0.04126906 0.007522583 -0.231073 0.03757238 0.002254724 -0.2381045 0.01962387 0.0401985 -0.2361275 0.03643667 0.002254009 -0.2484007 0.02165746 0.03744029 -0.2296648 0.02352267 0.03441399 -0.2258929 0.03440308 0.005012214 -0.2548634 0.04475456 0.02750921 -0.2652447 0.05484038 0.02481943 -0.2652125 0.04316794 0.03241318 -0.2645651 0.04814022 0.02253437 -0.2229995 0.04617965 0.02736186 -0.2222383 0.03550928 0.03516793 -0.2621909 0.03411972 0.04084277 -0.2577899 0.04875594 0.01778209 -0.2248373 0.04947149 0.01359832 -0.2278096 0.03331339 0.04571539 -0.2486843 0.0461176 0.005786597 -0.2379682 0.03397417 0.04601323 -0.2383509 0.0456708 0.005290091 -0.2461787 0.03548336 0.04279392 -0.2309215 0.04213029 0.04116827 -0.2274399 0.04913657 0.0077129 -0.2514107 0.04297101 0.03696507 -0.2245548 0.05499297 0.03506004 -0.2234495 0.04821026 0.009996592 -0.2559767 0.04701834 0.01328307 -0.2598354 0.04551076 0.01735591 -0.2627465 0.04948085 0.03842365 -0.2630026 0.04890799 0.04263651 -0.2600382 0.04851216 0.04603374 -0.2561438 0.04827618 0.04942494 -0.2486405 0.05539804 0.01117241 -0.2319307 0.05563402 0.007781267 -0.2394341 0.04876542 0.04922181 -0.2382956 0.05535167 0.007545948 -0.2467412 0.04957878 0.0460785 -0.2317404 0.0698657 0.03028857 -0.2660554 0.06979364 0.03533935 -0.2654707 0.06973087 0.04011636 -0.2637159 0.06968593 0.04435974 -0.2608782 0.07061606 0.02011376 -0.2256449 0.07047796 0.02512484 -0.2236849 0.07051265 0.03036797 -0.223074 0.06966787 0.04782885 -0.2571007 0.07066774 0.01584124 -0.2286787 0.06365138 0.05009746 -0.2520326 0.07068991 0.01244086 -0.2326382 0.06368499 0.05133205 -0.2469988 0.06978183 0.05175548 -0.2423528 0.07068049 0.01010239 -0.2372809 0.06987154 0.05058556 -0.2372456 0.07064181 0.008949339 -0.24233 0.06998085 0.04820472 -0.2325586 0.07057648 0.009036004 -0.2474921 0.07010376 0.0447483 -0.228581 0.07023686 0.0404213 -0.2255589 0.07048904 0.01034641 -0.2524714 0.07038515 0.01279598 -0.2569857 0.07027131 0.01623654 -0.2607821 0.07015913 0.02046573 -0.2636515 0.07838129 0.05028808 -0.2521954 0.07842701 0.05152285 -0.2471617 0.1095819 0.02756726 -0.2657919 0.1071859 0.02261292 -0.2651945 0.09841567 0.03402495 -0.2652975 0.1075701 0.02251762 -0.2234587 0.1107386 0.02719038 -0.2227324 0.09892249 0.03888112 -0.2634026 0.09935003 0.04313284 -0.2603896 0.09599435 0.0190221 -0.2253692 0.09966725 0.0465312 -0.2564442 0.0955404 0.01479077 -0.2282653 0.09985256 0.04888182 -0.2518063 0.09519964 0.01135635 -0.2320978 0.0998947 0.05005568 -0.2467543 0.09498667 0.0089221 -0.2366524 0.09979218 0.04999572 -0.2415854 0.09491431 0.007635772 -0.2416703 0.09954941 0.0487172 -0.2365981 0.0949862 0.007580697 -0.246863 0.09918016 0.04630362 -0.2320741 0.1088188 0.0417633 -0.2280685 0.0951969 0.008769452 -0.2519276 0.1082128 0.03758984 -0.2252183 0.107694 0.03284758 -0.2234334 0.09553366 0.01114076 -0.2565644 0.1055324 0.01348668 -0.2603083 0.1062558 0.01775681 -0.263324 0.1309614 0.02865529 -0.2644652 0.1315235 0.03347039 -0.262635 0.13021 0.03809344 -0.2596989 0.1264982 0.01395344 -0.2246486 0.1306068 0.04150217 -0.255804 0.1256313 0.009787559 -0.2276254 0.1308098 0.04389405 -0.251204 0.1250026 0.006429255 -0.2315306 0.1307882 0.04513454 -0.2461683 0.1246123 0.004079759 -0.2361364 0.1305277 0.04515612 -0.2409912 0.1244654 0.002876877 -0.2411746 0.1300275 0.04396241 -0.235974 0.1245525 0.002891898 -0.2463528 0.1292932 0.04162889 -0.2314082 0.1248528 0.004124701 -0.2513715 0.1235131 0.006788611 -0.2559404 0.2258134 -8.88773e-4 -0.260918 0.1958444 0.02457708 -0.2572135 0.1963017 0.02797132 -0.2533072 0.1965513 0.03034716 -0.2486991 0.1965681 0.03157085 -0.2436596 0.1963503 0.0315746 -0.238483 0.1959021 0.0303632 -0.23347 0.1952369 0.02801233 -0.2289106 0.2066074 0.02232706 -0.2246836 0.2049086 0.01827776 -0.2217628 0.2261454 0.009380877 -0.2191634 0.1895081 -0.006841719 -0.2534376 0.2028747 -0.005882322 -0.256929 0.2027474 -0.001525342 -0.259872 0.2298767 0.003958463 -0.2614941 0.2104638 0.01242303 -0.261536 0.2110446 0.01718294 -0.2597603 0.2080953 0.002315938 -0.2197933 0.2063732 0.007916152 -0.219225 0.2067462 -0.002478778 -0.2217534 0.1915205 -0.003772675 -0.2251356 0.1911098 -0.007178485 -0.2290353 0.1908941 -0.009565591 -0.2336397 0.190901 -0.01079934 -0.2386782 0.1911435 -0.01081275 -0.2438563 0.1916158 -0.009609341 -0.2488728 0.224985 0.01982086 -0.2563806 0.2253522 0.02323257 -0.252496 0.2203577 -0.008384287 -0.2242549 0.2255637 0.02562648 -0.2479038 0.2199905 -0.01179605 -0.2281395 0.225607 0.02686333 -0.2428706 0.2197791 -0.01418989 -0.2327316 0.2254797 0.02687132 -0.2376891 0.2197358 -0.01542681 -0.2377648 0.2251892 0.02565002 -0.2326604 0.2198631 -0.0154348 -0.2429464 0.2247523 0.0232703 -0.2280766 0.2201536 -0.0142135 -0.2479751 0.2205904 -0.01183378 -0.2525589 0.2528328 0.008016049 -0.2606246 0.2531331 0.01290732 -0.2587122 0.2533681 0.01717853 -0.2556787 0.2521371 -0.007324874 -0.2207645 0.2533234 -0.002563834 -0.2189269 0.2523439 0.002649664 -0.2182776 0.2543483 0.02039623 -0.2518714 0.251719 -0.0115872 -0.223735 0.2535979 0.0227555 -0.2474822 0.2514153 -0.01501405 -0.2276452 0.2535259 0.02401858 -0.242467 0.2512023 -0.01740247 -0.2322634 0.2525225 0.02409738 -0.237091 0.2510673 -0.01861321 -0.2373168 0.2541091 0.02269655 -0.2320457 0.2510018 -0.0185787 -0.2425063 0.2528206 0.02045905 -0.2276445 0.2523472 0.01704287 -0.2237411 0.2509899 -0.01730614 -0.2475283 0.2516071 0.01279437 -0.2207742 0.2510046 -0.01487481 -0.2520932 0.250985 -0.01142722 -0.2559416 0.2507817 -0.007158398 -0.2588569 0.3712848 -0.01570558 -0.2524587 0.3717763 -0.01812237 -0.2478886 0.3725948 -0.01937431 -0.2428851 0.4056624 -0.01964241 -0.2394036 0.3726428 0.001966714 -0.2187353 0.3727532 0.007117927 -0.2193652 0.3705608 -0.01812511 -0.2325598 0.3728057 0.01196843 -0.2212101 0.3713703 -0.01572704 -0.227999 0.372819 0.01623535 -0.2241622 0.3718623 -0.01229572 -0.224131 0.3728212 0.01967066 -0.22805 0.37221 -0.008031904 -0.2211918 0.3733424 0.02204406 -0.2326211 0.3718896 0.02331751 -0.2375808 0.3724643 -0.003183424 -0.2193567 0.4056759 0.02304589 -0.2445721 0.3701457 0.02208662 -0.2477893 0.371533 0.01963037 -0.2525192 0.3708443 0.01609563 -0.2564289 0.3706778 0.01176583 -0.2593528 0.3705616 0.006871998 -0.2611426 0.3698705 0.00185281 -0.2616564 0.3705679 -0.0031538 -0.2610805 0.3707215 -0.007997334 -0.2592534 0.3709535 -0.01226389 -0.2563226 0.4087589 0.001515269 -0.2654001 0.4088445 -0.003627717 -0.2647911 0.4088363 0.006655931 -0.2647722 0.4141787 -0.00369507 -0.2233749 0.4144393 0.001451849 -0.2227714 0.4090492 0.01149696 -0.2629407 0.4093592 0.01575779 -0.2600082 0.4137483 -0.008540153 -0.2251814 0.4096902 0.01919239 -0.2561364 0.4131411 -0.01280057 -0.2280812 0.4324183 0.0212565 -0.2544315 0.4123318 -0.01622748 -0.2318967 0.4341136 -0.01897162 -0.2393321 0.4372465 0.02241301 -0.2449322 0.4136499 0.02156192 -0.2366523 0.4355735 -0.02025544 -0.2500029 0.4139517 0.01915496 -0.2320638 0.4142532 0.01571732 -0.2281911 0.4109714 -0.01861584 -0.2517407 0.41446 0.01144951 -0.22525 0.4145289 0.006600141 -0.2234082 0.4101406 -0.01619267 -0.256255 0.4095305 -0.01274597 -0.2600792 0.4090993 -0.008475065 -0.2629817 0.4549785 6.11533e-4 -0.2731251 0.4550737 -0.004533946 -0.2725208 0.4551187 0.005754172 -0.2725031 0.462897 -0.004643261 -0.2315066 0.4632235 4.98827e-4 -0.2309188 0.4554712 0.01059627 -0.2706876 0.4559898 0.01485687 -0.2677785 0.4623337 -0.009481906 -0.2332841 0.4565953 0.01828938 -0.2639344 0.4615375 -0.01373499 -0.2361416 0.4604982 -0.01715427 -0.2399013 0.4618031 0.02062147 -0.2447372 0.462316 0.01820904 -0.2401636 0.4628113 0.01476591 -0.2363132 0.4579883 -0.01953428 -0.2596377 0.4631603 0.0104947 -0.2333903 0.4633092 0.005644679 -0.2315583 0.4568496 -0.01710659 -0.2640815 0.4560093 -0.01365709 -0.2678583 0.4554162 -0.009383738 -0.270729 0.5451095 -0.001651406 -0.2923388 0.5447839 -0.006765604 -0.2916238 0.545291 0.003524959 -0.2917445 0.5546412 -0.006890058 -0.25107 0.5555774 -0.001805603 -0.2505956 0.5454744 0.00840944 -0.2898946 0.5455352 0.01267707 -0.2869036 0.5547243 -0.01174199 -0.2529952 0.5778843 0.01555597 -0.2892187 0.5544373 -0.01599824 -0.2559691 0.5786155 0.01791268 -0.2847264 0.5541062 -0.01940453 -0.2598598 0.5794122 0.01906442 -0.2800362 0.5801171 -0.02245837 -0.2697192 0.5801101 0.01911371 -0.2749692 0.5794255 -0.02363252 -0.2747065 0.5807436 0.01799535 -0.2701118 0.5787205 -0.02364754 -0.2796422 0.5551838 0.01594746 -0.2598791 0.5551952 0.01248955 -0.2559295 0.5779405 -0.02244609 -0.2846016 0.5557687 0.008200407 -0.2530747 0.5555187 0.003345012 -0.2511786 0.5464886 -0.01928991 -0.283127 0.5458148 -0.01587164 -0.2869416 0.5455249 -0.01160532 -0.2899017 0.576844 -0.018386 -0.290883 0.5762801 -0.01340866 -0.2950193 0.5827866 -0.004868745 -0.2557294 0.5813153 0.01703298 -0.267207 0.5760236 -0.007661581 -0.2974708 0.5823372 -0.01263016 -0.2581575 0.5821718 0.01305824 -0.2619532 0.5826151 0.009112596 -0.2588168 0.5829752 0.002870202 -0.2561847 0.5814191 -0.01845324 -0.2627473 0.5759943 -0.001556336 -0.298138 0.5763766 0.005869567 -0.2966745 0.5772144 0.01231706 -0.2926414 0.628708 0.004383563 -0.2742404 0.6245629 0.008675158 -0.2666872 0.6001952 -0.03216588 -0.2855085 0.5909604 -0.03119748 -0.2802835 0.5909507 -0.02945798 -0.2900611 0.6002111 -0.03218179 -0.2750898 0.6094551 -0.0294435 -0.2705654 0.6002369 -0.02863341 -0.2652939 0.6094833 -0.02450966 -0.2619895 0.6178179 -0.01827335 -0.2617595 0.6095162 -0.01694029 -0.2556183 0.6178466 -0.01099854 -0.2575446 0.5826465 -0.002539157 -0.3046401 0.5826232 -0.01089113 -0.3031806 0.6245342 -0.002731978 -0.2625553 0.6178741 -0.002720892 -0.256072 0.5909664 -0.01686191 -0.3050262 0.5909528 -0.02447932 -0.2986542 0.5826072 -0.01824021 -0.2989525 0.628679 -0.001104652 -0.2710694 0.6001912 -0.02858752 -0.2952934 0.6094351 -0.03114664 -0.2803116 0.6177915 -0.02366781 -0.2682084 0.5826743 0.005808234 -0.3031551 0.6244269 -0.01151585 -0.2650822 0.5909897 -0.007524549 -0.3084086 0.6001995 -0.02187836 -0.3032643 0.6094255 -0.0294137 -0.2900526 0.6177707 -0.02653133 -0.2761134 0.5827032 0.01314437 -0.2989046 0.6244739 -0.01807737 -0.2714468 0.5910201 0.002406477 -0.3083935 0.6289738 -0.008452534 -0.27373 0.6002191 -0.01284754 -0.3084599 0.6094276 -0.02445369 -0.2986133 0.6177579 -0.02651846 -0.2845211 0.5827297 0.01858431 -0.2924014 0.5910538 0.01173347 -0.3049826 0.6002477 -0.002584397 -0.3102535 0.609441 -0.01686483 -0.3049615 0.6177546 -0.02363079 -0.2924173 0.5827507 0.02147191 -0.2844298 0.5841054 0.02284669 -0.2784374 0.6243768 -0.02028107 -0.2803177 0.5910868 0.01933139 -0.2985874 0.6002819 0.007673144 -0.3084287 0.6094643 -0.007562518 -0.3083312 0.6177614 -0.01821666 -0.2988497 0.6244468 -0.01805043 -0.2891821 0.5911151 0.02428376 -0.2899792 0.591326 0.02605253 -0.2801966 0.5982137 0.02730959 -0.2802051 0.6287199 -0.01187539 -0.2822405 0.6003174 0.01668798 -0.3032056 0.6094945 0.002331256 -0.3083161 0.6177772 -0.01092898 -0.3030424 0.60035 0.02337276 -0.2952142 0.6095281 0.01162326 -0.304918 0.6178003 -0.002646863 -0.3044898 0.6243805 -0.0114693 -0.2955266 0.6003759 0.02692121 -0.2854184 0.6052053 0.02693587 -0.2802163 0.609561 0.01919263 -0.2985468 0.6178278 0.005630731 -0.3030172 0.6244802 -0.002676725 -0.2980269 0.6286956 -0.007232367 -0.2883422 0.6095892 0.02412647 -0.2899709 0.6119198 0.02495187 -0.2802296 0.6178565 0.01290553 -0.2988022 0.6178828 0.01829999 -0.2923534 0.6245213 0.008716881 -0.2938601 0.6286497 -0.001068592 -0.289521 0.6179037 0.02116352 -0.2844484 0.6180095 0.02142429 -0.2775298 0.6230898 0.01666671 -0.2802593 0.6244719 0.01382213 -0.2862775 0.626937 0.01081687 -0.2802741 0.6287052 0.004416942 -0.2862653 0.6289433 0.005980849 -0.2802954 0.629985 -4.73547e-4 -0.2772709 0.5911449 0.02425384 -0.2704187 0.5911428 0.01927518 -0.2618257 0.6003917 0.02690523 -0.2749997 0.5911293 0.01165777 -0.2554537 0.6003958 0.02332687 -0.2652148 0.591106 0.002320408 -0.2520713 0.6299543 -1.33396e-4 -0.283179 0.6003875 0.01661771 -0.2572438 0.6096189 0.02409666 -0.2704838 0.5910756 -0.007610619 -0.2520864 0.6003678 0.007586896 -0.2520482 0.6096168 0.01913666 -0.261923 0.5826376 -0.02373731 -0.2680529 0.5910419 -0.01693761 -0.2554973 0.6003392 -0.002676129 -0.2502546 0.6301637 -0.00452888 -0.2797924 0.6096033 0.0115478 -0.2555749 0.6179197 0.01826298 -0.2681445 0.6297311 -0.005265355 -0.2846629 0.5826166 -0.02662497 -0.2760245 0.5910089 -0.02453547 -0.2618925 0.6003051 -0.01293379 -0.2520795 0.6095801 0.002245485 -0.2522052 0.617913 0.01284879 -0.2617121 0.5826037 -0.02661198 -0.2845031 0.6244902 0.01380372 -0.2742541 0.5909806 -0.0294879 -0.2705006 0.6002695 -0.02194863 -0.2573026 0.6095498 -0.007648289 -0.2522202 0.6178972 0.005561172 -0.2575193 0.5826005 -0.02369999 -0.2924659 + + + + + + + + + + -0.6358479 0.4847084 -0.6006291 -0.5980837 0.3629737 -0.7145251 -0.7430328 0.5652988 -0.3582454 0.6791619 -0.4382577 0.5887863 0.53789 -0.387151 0.7488582 -0.7362297 0.5677115 -0.3683334 0.6996514 -0.6117433 0.3691315 -0.725387 0.6880917 0.01853168 0.7054873 -0.6013194 0.3751034 -0.649928 0.6965017 0.3041036 -0.7459482 0.658191 0.1017157 0.7514357 -0.6593505 -0.02452176 -0.5819312 0.6204267 0.525763 -0.4173322 0.5741343 0.7044172 -0.5805107 0.6026377 0.5475721 0.6931613 -0.6492675 -0.3130164 0.6885873 -0.7199182 -0.08697956 -0.3238823 0.463804 0.8246127 0.5464095 -0.6561483 -0.5204864 0.09671378 -0.3204988 -0.9422988 -0.06994038 -0.1390371 -0.9878143 -0.06700223 -0.1437348 -0.9873455 -0.208576 0.01211458 -0.9779312 -0.2209991 0.03266394 -0.9747269 -0.3787696 0.215566 -0.900036 -0.3697654 0.198524 -0.9076684 0.2210006 -0.03765279 0.9745466 0.2342124 -0.04798603 0.9710006 -0.4850112 0.3940535 -0.7806958 -0.4679677 0.3258803 -0.8214672 0.4104893 -0.2531884 0.8760104 0.3827363 -0.2315328 0.8943744 -0.5771443 0.5400796 -0.6125509 -0.5772036 0.5406122 -0.6120249 0.485759 -0.3949041 0.7798007 0.5387828 -0.4178507 0.7315149 -0.6455109 0.6467109 -0.4063015 -0.6405529 0.666896 -0.3807122 0.5776942 -0.5406081 0.6115654 0.5773444 -0.5404878 0.6120021 -0.6466226 0.733735 -0.2085958 0.6189165 -0.6688095 0.4118692 0.6407434 -0.6667312 0.3806801 -0.634454 0.7669926 0.09586715 -0.6789192 0.7341654 0.008366405 0.6790283 -0.7122128 0.1779707 -0.5865055 0.7552031 0.2927112 -0.5879483 0.7550442 0.2902159 0.6411958 -0.7654272 -0.05467313 0.6271934 -0.7788603 0.00229007 -0.4983877 0.700659 0.5105751 -0.5005146 0.7010342 0.5079725 -0.3812546 0.6053312 0.6987268 -0.3838922 0.6062416 0.6964897 0.5879911 -0.75568 -0.2884689 0.5881341 -0.7548839 -0.2902562 -0.225373 0.4507761 0.8637176 -0.2112787 0.442278 0.8716374 -0.08980709 0.3133193 0.9453919 -0.09722751 0.3187715 0.9428317 0.521477 -0.6855877 -0.5079679 0.06673431 0.1426158 0.9875259 0.5404442 -0.728648 -0.4207045 0.07074064 0.139538 0.9876867 0.3952032 -0.5853073 -0.7079759 0.4196491 -0.6290397 -0.6543729 0.2470338 -0.4657455 -0.8497385 0.2566465 -0.4812386 -0.8381778 0.0920549 -0.313121 -0.9452413 -0.6209276 -0.7682899 0.155498 -0.5771306 -0.8095033 0.1078177 -0.6280639 -0.7599424 0.1674017 -0.6465252 -0.7542642 0.1144148 -0.6285077 -0.7597599 0.1665622 -0.6281002 -0.7595593 0.1689969 -0.6281893 -0.7600272 0.1665441 -0.5889493 -0.7765585 0.2238213 -0.6253878 -0.7611395 0.1719215 -0.6281874 -0.7600289 0.1665431 -0.6284151 -0.7599652 0.1659746 -0.6281909 -0.760026 0.1665437 -0.6262688 -0.7615388 0.1668717 -0.6287673 -0.7605478 0.1619222 -0.6281355 -0.7600038 0.1668539 -0.6289209 -0.7581722 0.1721441 -0.6281893 -0.7600273 0.1665436 -0.5756139 0.8176209 -0.0128445 -0.5832665 0.8006243 -0.1371169 -0.1964113 0.1199028 -0.9731628 -0.2826125 0.2838659 -0.9162698 -0.2821385 0.2803697 -0.9174916 -0.3777958 0.5194132 -0.7664726 -0.374789 0.4693305 -0.7995387 0.2608996 -0.2421861 0.9344931 -0.4601974 0.6220238 -0.6334862 0.3750804 -0.4723783 0.7976049 0.3768075 -0.4734799 0.7961363 -0.4728316 0.7773481 -0.4149222 -0.4789523 0.7625366 -0.4349055 0.4133742 -0.6168595 0.6697807 0.4469286 -0.6338963 0.6312134 -0.5170533 0.8244113 -0.2302217 0.5110247 -0.794973 0.3269124 0.4668075 -0.7714645 0.4323581 -0.4704034 0.8809284 0.05182594 -0.4315264 0.8940474 0.1202672 0.4800717 -0.8522931 0.2076725 -0.4668003 0.8414558 0.272121 0.5247185 -0.8493099 -0.05782151 0.5138797 -0.8571194 -0.03569406 -0.3938136 0.7941516 0.4628545 -0.3716228 0.7899542 0.4877182 -0.2934683 0.6695591 0.6823248 -0.2931019 0.6693603 0.6826771 0.426289 -0.8651573 -0.2641602 -0.2027592 0.5418188 0.8156722 0.3938613 -0.7941263 -0.4628574 0.4030734 -0.771308 -0.4925607 0.2758697 -0.6459773 -0.711765 -0.0337063 -0.1382622 -0.989822 0.04723107 -0.3505061 -0.9353687 -0.1278913 0.09544378 -0.9871851 -0.04343932 -0.1230308 -0.9914517 0.131437 -0.1021066 0.986052 -0.1852587 0.2932696 -0.9379085 -0.1062833 0.0593698 -0.9925619 -0.207803 0.3196552 -0.9244667 -0.2823935 0.5437631 -0.790301 0.2130818 -0.3282663 0.9202378 0.1300494 -0.09298437 0.9871378 -0.298331 0.5571975 -0.7749386 0.2594422 -0.5294479 0.8076972 0.219163 -0.3967273 0.8913894 -0.343799 0.8149467 -0.4665451 0.3187244 -0.7450202 0.585969 0.259718 -0.5268239 0.8093226 -0.3719226 0.8248945 -0.4257025 -0.3494222 0.9369539 -0.004659175 0.335957 -0.8300145 0.4452064 -0.3698002 0.9282182 0.04072809 0.3812599 -0.9238009 0.0351119 -0.2813183 0.8583438 0.4290757 -0.2007056 0.6831485 0.7021577 -0.2863628 0.8453864 0.4509082 0.348228 -0.9171129 -0.1940138 0.3197833 -0.9468364 -0.03520953 -0.128376 0.5436465 0.8294385 -0.2027384 0.7124098 0.6718403 -0.03732359 0.3147706 0.9484337 -0.1250002 0.5050061 0.8540163 0.2508131 -0.8444675 -0.4732521 0.04683828 0.1027122 0.9936078 -0.04375845 0.3416026 0.9388253 0.04214429 0.127433 0.9909515 0.2712091 -0.8515083 -0.4487529 0.2034879 -0.7134477 -0.670511 0.2452545 -0.7461555 -0.6189526 0.139132 -0.5412336 -0.8292819 0.1460501 -0.5491519 -0.8228618 0.07307368 -0.3940753 -0.9161686 -0.1431236 0.3871052 -0.9108596 -0.1902987 0.5475143 -0.8148708 -0.1803207 0.5748422 -0.7981484 -0.1884031 0.7305046 -0.6564049 -0.2186126 0.8866121 -0.4075875 -0.2502917 0.8442372 -0.4739384 0.2166981 -0.672602 0.7075653 0.2469354 -0.8800973 0.4055263 0.2519664 -0.8815932 0.399132 -0.2120074 0.9768315 0.02920812 -0.2405797 0.9705478 -0.01258599 0.2281261 -0.973371 0.02252459 0.2119147 -0.9761335 0.04749274 -0.1789085 0.8783085 0.4433578 -0.1936134 0.8852427 0.4229176 -0.1418163 0.7651631 0.6280236 0.1999812 -0.9328963 -0.2995199 -0.04468035 0.1142387 -0.9924482 -0.02177459 -0.09357923 -0.9953737 -0.06957495 0.3431763 -0.9366907 -0.04715061 0.1221502 -0.9913911 -0.05926752 0.3089997 -0.9492137 -0.07549786 0.5537588 -0.8292475 0.07046824 -0.3616759 0.9296369 0.04388934 -0.1159148 0.9922891 0.05071419 -0.1354308 0.9894881 -0.0880776 0.7334553 -0.6740072 -0.08013075 0.5663074 -0.8202896 0.09143358 -0.5757894 0.8124695 -0.09565418 0.8612663 -0.4990698 0.07198959 -0.3516229 0.9333697 -0.09310758 0.7455832 -0.6598763 0.1063657 -0.7540526 0.6481443 -0.09448432 0.9670143 -0.2365505 -0.1302878 0.9019411 -0.411737 0.09347218 -0.5659516 0.8191226 -0.131009 0.987994 0.08188152 0.09447175 -0.8891845 0.4476896 0.09363931 -0.7932739 0.6016215 -0.07393211 0.9718004 0.2239153 -0.1149083 0.9930632 0.02493447 0.1178604 -0.9683042 0.2202178 0.08092021 -0.9073094 0.4126034 -0.07990872 0.8879623 0.4529213 0.07419455 -0.9970871 -0.01768004 -0.0521683 0.7529985 0.655951 -0.07572114 0.8954104 0.4387556 -0.03967696 0.5713256 0.8197639 -0.06212258 0.7092542 0.7022103 0.08171993 -0.9634834 -0.2549932 0.09874427 -0.994713 0.02821218 -0.01859277 0.4114109 0.9112603 -0.04050099 0.5599272 0.8275514 0.08423846 -0.8750022 -0.4767338 0.01719963 0.1361629 0.9905372 0.1113706 -0.9767567 -0.1831476 0.0905593 -0.883223 -0.4601262 0.06269568 -0.7385781 -0.6712464 0.06830394 -0.7490037 -0.6590358 0.0374909 -0.560378 -0.827388 0.04188829 -0.5706731 -0.8201083 0.005588948 -0.3200173 -0.9473953 -0.0151987 0.9711253 -0.2380856 -0.01640635 0.9052026 -0.4246636 -0.01371091 0.9972458 -0.07288956 -0.01519846 0.9711248 -0.2380877 -0.001564741 -0.1189647 -0.9928973 -0.00546205 -0.1376373 -0.9904677 0.0103473 0.09410291 -0.9955087 0.01447814 0.1151745 -0.9932398 -0.01951092 -0.1406142 0.9898722 0.0252853 0.3611122 -0.9321795 0.02152252 0.3449869 -0.9383608 -0.01418465 -0.1156356 0.9931905 0.0372551 0.5752923 -0.817099 0.03243482 0.5558421 -0.8306549 -0.02745884 -0.4078835 0.912621 -0.03131908 -0.3648357 0.9305451 0.04696977 0.7549695 -0.6540756 0.04156988 0.7359897 -0.6757154 -0.03745555 -0.5616697 0.8265135 -0.03375101 -0.5788917 0.8147057 0.06642997 0.8889316 -0.4531973 0.04829013 0.8559067 -0.5148708 -0.04757153 -0.7417799 0.6689541 -0.04283082 -0.7580733 0.6507614 0.07068806 0.9714838 -0.2263237 0.0677694 0.9688303 -0.2382755 -0.05493122 -0.8795349 0.4726533 -0.0493769 -0.8919726 0.4493851 0.05820953 0.9982231 0.01274496 0.06665408 0.9951977 0.07168573 -0.05908 -0.966782 0.2486807 -0.05302864 -0.9734438 0.2226997 0.05538398 0.9665399 0.2504661 0.05141526 0.973659 0.2221367 -0.05976217 -0.9981651 0.009756326 -0.05359649 -0.9984331 -0.01608467 0.04941093 0.8795318 0.4732679 0.0462445 0.8910488 0.4515457 0.0457794 0.713766 0.6988865 0.03828209 0.7548572 0.6547711 -0.05693143 -0.971435 -0.2303758 -0.05106592 -0.9660307 -0.2533317 0.03434646 0.5602278 0.8276262 0.03333544 0.5729673 0.8189 0.0144425 0.3508424 0.9363232 0.01587986 0.3266735 0.9450039 -0.05075579 -0.8876779 -0.4576591 0.001344501 0.1236687 0.9923227 -0.04560095 -0.8784655 -0.4756248 0.003531038 0.09138083 0.9958097 -0.03753912 -0.7410094 -0.6704446 -0.05221825 -0.7775405 -0.6266611 -0.03270125 -0.5617477 -0.8266621 -0.03553032 -0.5724793 -0.8191491 -0.02214497 -0.4055501 -0.9138045 -0.0147258 -0.3569586 -0.9340041 0.08096855 0.3458614 -0.9347856 0.05263376 0.166397 -0.9846531 0.08084541 0.3549958 -0.9313657 0.111544 0.555154 -0.8242342 0.1354053 0.7387025 -0.660291 0.1108831 0.5671768 -0.8160978 -0.1127505 -0.5620405 0.8193888 -0.07049024 -0.2884728 0.9548899 0.1516419 0.8742149 -0.4612519 0.1346678 0.7453961 -0.6528777 -0.1370463 -0.7400299 0.6584634 -0.1095662 -0.5533733 0.8256956 0.1590584 0.9587694 -0.2355033 0.1504738 0.8793821 -0.4517133 -0.1533856 -0.8749278 0.4593194 -0.1337488 -0.7320978 0.6679402 0.1572406 0.9875531 0.003792822 0.1574428 0.9616122 -0.2247529 -0.1608076 -0.9589375 0.2336235 -0.1502503 -0.868987 0.4714727 0.1463088 0.9589919 0.2427514 0.1552516 0.9877679 0.01454746 -0.1588957 -0.98728 -0.005533397 -0.1580953 -0.9559463 0.247331 0.1269064 0.8748269 0.4675176 0.1441096 0.9568573 0.2523027 0.1066115 0.7754145 0.6223878 0.1247321 0.8711361 0.4749357 -0.147771 -0.9583825 -0.2442682 -0.1567627 -0.9876014 0.008301377 -0.1278353 -0.8726589 -0.471301 -0.1462753 -0.961701 -0.2318075 -0.1265566 -0.8794097 -0.4589358 -0.09483939 -0.7097703 -0.6980198 0.01101237 -0.1249513 -0.9921018 -0.03626626 -0.3531624 -0.9348589 0.1758009 0.7328064 -0.6573347 0.1461351 0.5596064 -0.8157728 0.1960123 0.8672161 -0.4577286 0.1757605 0.7318514 -0.6584086 0.2047921 0.9510091 -0.2316074 0.1960383 0.8664468 -0.4591722 0.2016586 0.9794251 0.007771849 0.2049034 0.9505741 -0.2332885 0.1868238 0.9509646 0.2465023 0.2018538 0.9793969 0.00607109 0.161176 0.8674146 0.4707592 0.1870748 0.9513065 0.2449876 0.1289892 0.7447753 0.6547302 0.1614441 0.8680014 0.4695842 0.08275216 0.5599192 0.8244044 0.1175765 0.7121029 0.6921599 0.04016435 0.3673623 0.9292103 0.08104944 0.5540581 0.8285232 -0.01278811 0.1161651 0.9931476 0.03531146 0.3486577 0.9365847 -0.1626996 -0.8723973 -0.4609252 -0.1244043 -0.7264334 -0.6758832 -0.1295194 -0.7616897 -0.6348651 -0.08269482 -0.5594859 -0.8247044 -0.08361768 -0.5653555 -0.8205981 -0.033423 -0.3357604 -0.9413543 0.01056253 -0.1267473 -0.9918788 0.06650829 0.1476505 -0.9868009 0.05622649 0.1057602 -0.9928008 0.1027857 0.3366345 -0.9360088 0.1043677 0.3426911 -0.9336328 -0.06005972 -0.1190389 0.9910715 -0.05932575 -0.1139028 0.9917191 0.1476878 0.5796247 -0.8013885 -0.1053903 -0.3507376 0.9305247 -0.1071147 -0.3652215 0.9247378 -0.1406967 -0.5301151 0.8361714 -0.143297 -0.5554736 0.819094 -0.1755693 -0.7322569 0.6580086 -0.1755673 -0.7322713 0.657993 -0.195729 -0.8668337 0.4585734 -0.1957291 -0.866748 0.4587352 -0.2044785 -0.9508475 0.2325463 -0.2045028 -0.9507456 0.2329412 -0.2013279 -0.9794998 -0.006885588 -0.2014004 -0.9794892 -0.006225347 -0.1864823 -0.9512251 -0.2457545 -0.1866266 -0.9514214 -0.2448835 -0.01204812 0.1208533 0.9925973 -0.1630069 -0.8752413 -0.4553918 0.1084632 0.5156867 -0.8498841 0.1387672 0.7375454 -0.6608862 0.1394979 0.7393208 -0.6587452 -0.1216848 -0.6116032 0.7817509 0.1547399 0.8731276 -0.4622812 0.1554855 0.8745573 -0.4593188 -0.1384294 -0.7375985 0.6608977 -0.1382786 -0.7386942 0.6597045 0.1617351 0.9579985 -0.2368136 0.1623973 0.9587379 -0.2333429 -0.1543259 -0.8731942 0.4622936 -0.1540549 -0.8742163 0.4604488 0.1593332 0.9872221 0.002390623 0.1598589 0.9871216 0.006007075 -0.1612562 -0.9580754 0.2368291 -0.1608568 -0.9587078 0.2345306 0.1476746 0.9591054 0.2414726 0.1480404 0.9582087 0.244786 -0.1588182 -0.987305 -0.002377271 -0.1583024 -0.9873788 -0.004850149 0.1274403 0.875265 0.4665515 0.1276562 0.8738284 0.4691779 0.09402233 0.7082522 0.6996704 -0.1471536 -0.9591884 -0.2414609 -0.1465648 -0.9586899 -0.2437877 -0.1273862 -0.8752769 -0.4665439 -0.1260302 -0.8730201 -0.4711183 -0.1069276 -0.7753395 -0.6224269 0.05751848 0.360463 -0.9309985 0.02751582 0.05817824 -0.997927 0.05815988 0.3426905 -0.9376465 0.07863777 0.5743779 -0.8148045 -0.055422 -0.3474807 0.9360479 -0.03297007 -0.1296092 0.9910169 -0.03318744 -0.1109982 0.9932664 0.08603316 0.7499032 -0.6559295 0.07621008 0.6088805 -0.7895926 -0.07820081 -0.5648434 0.8214843 -0.05905932 -0.3634528 0.9297388 0.09629738 0.8834972 -0.4584318 0.08707636 0.7444061 -0.6620252 -0.08711683 -0.7458302 0.6604151 -0.06684017 -0.5158334 0.8540775 0.1024547 0.964963 -0.2415564 0.09716451 0.8807106 -0.4635817 -0.09758442 -0.882161 0.460727 -0.08664953 -0.7444548 0.6620265 0.1013062 0.9948459 0.004323899 0.101858 0.9658529 -0.2382289 -0.1023287 -0.9667496 0.2343588 -0.09695041 -0.880733 0.4635841 0.09385937 0.9665133 0.2388356 0.1020199 0.9947819 9.69753e-4 -0.1011013 -0.9948619 -0.005347907 -0.1016361 -0.9658753 0.2382334 0.07976859 0.8789475 0.4702003 0.09357464 0.9662328 0.2400788 0.06463462 0.7470341 0.6616362 0.08111447 0.8814129 0.4653297 -0.09398949 -0.9651258 -0.2443323 -0.1004395 -0.9949428 -9.32202e-4 0.04845416 0.5661836 0.8228538 0.07674384 0.7759577 0.6260991 0.01730144 0.3182394 0.9478525 0.04963415 0.5704929 0.8198015 -0.08142447 -0.8795757 -0.4687395 -0.0934289 -0.9662486 -0.2400727 -0.00994271 0.09232825 0.995679 -0.0810064 -0.8814291 -0.465318 -0.06414318 -0.743456 -0.6657018 -0.06799638 -0.7140489 -0.696786 -0.04819798 -0.564877 -0.8237664 -0.04820215 -0.5600612 -0.8270479 -0.02968853 -0.4168877 -0.9084731 -0.00752449 -0.8825795 -0.4701032 -0.007102072 -0.9703426 -0.2416297 -0.007283091 -0.969342 -0.2456077 -0.006821036 -0.9999023 -0.01219969 -0.006563663 -0.9999569 -0.006574749 0.003238439 0.1213091 0.9926095 0.004603207 0.1480619 0.9889674 -0.005473494 -0.9818459 0.1896015 -0.003327429 -0.9724519 0.23308 0.005783379 0.3554421 0.9346805 0.007175445 0.3824898 0.923932 -0.003884255 -0.8848116 0.4659328 -0.004236042 -0.8881559 0.4595227 0.006687939 0.5689424 0.8223503 0.006846368 0.5717284 0.8204145 -0.002223014 -0.7479351 0.6637681 -0.002524495 -0.7519535 0.6592113 0.007160842 0.7493488 0.6621368 0.007344663 0.7520435 0.6590726 -4.11496e-4 -0.5675291 0.8233532 -6.67387e-4 -0.5717246 0.8204454 0.007081747 0.8871435 0.4614393 0.006494283 0.9690207 0.246894 0.001532614 -0.3540592 0.9352218 0.007387936 0.8905156 0.4548928 0.001197636 -0.3603438 0.9328188 0.003096342 -0.1198926 0.9927821 0.002940714 -0.123034 0.9923981 0.007387936 0.9641208 0.2653616 0.0062747 0.999944 -0.008527576 0.006477534 0.9998887 -0.01345002 0.004541099 0.9434584 -0.3314598 0.002820909 0.9697244 -0.2441859 0.003258943 0.8878545 -0.4601128 0.001139581 0.7416845 -0.6707479 0.003810226 0.8810831 -0.4729464 -1.34241e-4 0.5596334 -0.8287404 0.002911686 0.7633926 -0.6459282 0.001180529 0.5790073 -0.8153215 -0.001781165 0.343525 -0.9391419 -5.59243e-4 0.3641602 -0.9313362 -0.003382742 0.1022938 -0.9947485 0.001863658 0.1994478 -0.9799067 -0.002909243 -0.1146674 -0.9933997 -0.002891063 -0.115638 -0.9932872 -0.006296992 -0.334836 -0.9422554 -0.00556302 -0.3530972 -0.9355701 -0.006567716 -0.5664326 -0.8240819 -0.00667572 -0.5641722 -0.8256302 -0.007179677 -0.7470192 -0.6647638 -0.007313787 -0.744827 -0.6672175 -0.007368087 -0.8843038 -0.466854 -0.09726184 -0.1186315 -0.9881633 -0.09458178 -0.3539915 -0.9304538 -0.0940575 0.1220915 -0.9880521 -0.09614008 -0.1269444 -0.9872397 0.09394365 -0.120643 0.9882408 -0.08623456 0.355849 -0.9305564 -0.09315407 0.1140766 -0.989095 -0.08502888 0.3440258 -0.9351023 -0.07260543 0.5690225 -0.8191104 0.0853365 -0.3547286 0.9310668 0.09367424 -0.1224597 0.988043 -0.05476158 0.7492828 -0.6599821 -0.0717889 0.5600806 -0.8253218 0.07178366 -0.5681886 0.8197615 0.08499729 -0.3566031 0.9303815 -0.03905439 0.8559278 -0.5156184 -0.05442363 0.7454353 -0.6643525 0.05408626 -0.7485625 0.6608547 0.07135552 -0.5700438 0.8185099 -0.008309543 0.979691 -0.2003416 -0.03830319 0.882178 -0.469356 0.02881109 -0.9073956 0.4192889 0.05352407 -0.7503744 0.6588425 0.0215227 -0.9470549 0.3203493 0.03718984 -0.887194 0.4598955 0.03656697 0.9781311 0.2047497 0.02070301 0.997906 0.06127953 0.05668562 0.8856592 0.4608628 0.03548693 0.9704294 0.2387623 0.07368057 0.7486725 0.6588328 0.0564683 0.883432 0.4651444 -0.04455161 -0.9603199 -0.2753195 -0.01093959 -0.9995772 0.02694231 0.08667528 0.5681644 0.8183377 0.07355606 0.7473189 0.6603817 0.09463495 0.3546345 0.9302036 0.08653032 0.5666528 0.8194004 -0.05673772 -0.8839858 -0.4640584 0.09710568 0.1205061 0.9879518 -0.0355255 -0.9708349 -0.2371027 0.09445977 0.3530196 0.9308355 0.09688776 0.1187612 0.9881846 -0.05623602 -0.8850885 -0.462013 -0.07395356 -0.7466226 -0.6611244 -0.07359462 -0.7478322 -0.6597961 -0.08690702 -0.5659441 -0.8198504 -0.08662122 -0.5672699 -0.8189638 -0.09483146 -0.3524999 -0.9309946 -0.166011 -0.1180436 -0.9790332 -0.1610447 -0.3525592 -0.9218279 -0.1612641 0.1228212 -0.979239 -0.1659424 -0.1186873 -0.978967 0.1611733 -0.122173 0.979335 -0.1471564 0.3566316 -0.9225828 -0.1612092 0.1220387 -0.9793459 -0.1471248 0.3556544 -0.922965 -0.1245006 0.5697911 -0.8123041 0.1470944 -0.3561164 0.9227917 0.161056 -0.122985 0.9792526 -0.0946117 0.7499174 -0.6547309 -0.1245027 0.5686603 -0.8130957 0.1244934 -0.569297 0.8126515 0.1469245 -0.3569974 0.9224783 -0.05142247 0.908589 -0.4145139 -0.09466069 0.7487295 -0.656082 0.09468126 -0.7493606 0.6553581 0.1242182 -0.5703473 0.8119568 0.0698719 -0.8518636 0.5190821 0.09425771 -0.7505201 0.6540911 0.09388411 0.8848954 0.4562301 0.06734246 0.9546416 0.2900421 0.1239055 0.7475535 0.6525422 0.09393376 0.884167 0.4576299 0.1467073 0.5667759 0.8107046 0.1239107 0.7468703 0.6533229 0.1609765 0.3530683 0.921645 0.1466872 0.5661278 0.8111611 -0.09428399 -0.883639 -0.4585767 0.1658907 0.1188865 0.9789517 -0.05163055 -0.9797519 -0.1934441 0.1609335 0.3524234 0.9218992 0.1658192 0.1182093 0.9790458 -0.09394001 -0.8842962 -0.4573791 -0.1241808 -0.7462596 -0.6539693 -0.1239888 -0.746842 -0.6533405 -0.1469116 -0.5655446 -0.8115271 -0.1467882 -0.5660894 -0.8111696 -0.1611289 -0.3520306 -0.9220152 -0.2096185 -0.1222813 -0.9701069 -0.2033147 -0.3519273 -0.9136795 -0.2041649 0.118707 -0.9717127 -0.209868 -0.1178594 -0.9706002 0.2036083 -0.1280479 0.9706428 -0.1867871 0.3540789 -0.9163727 -0.2041928 0.1230173 -0.9711706 -0.1866686 0.3567933 -0.9153434 -0.1585149 0.5681892 -0.8074862 0.1861665 -0.3596075 0.9143438 0.2040368 -0.123953 0.9710843 -0.1134606 0.7765615 -0.619741 -0.1583488 0.5698483 -0.8063489 0.1576169 -0.5727174 0.8044574 0.1864536 -0.3578276 0.9149833 -0.07457149 0.8880164 -0.4537247 -0.118781 0.7498483 -0.6508599 0.1200161 -0.7519857 0.6481618 0.1580454 -0.5708873 0.8056734 -0.02629899 0.9718371 -0.2341814 -0.07769554 0.8782315 -0.4718823 0.0833615 -0.8683572 0.4888833 0.1204366 -0.7507554 0.6495086 0.02035194 0.9997144 -0.01253187 -0.03056925 0.9656174 -0.2581639 0.02377569 -0.973842 0.225979 0.07109791 -0.8931551 0.4440936 0.06779402 0.9741604 0.2154427 0.01986551 0.9996853 -0.01532196 -0.02171021 -0.9997454 0.006137728 0.02243453 -0.9750982 0.2206363 0.1207937 0.8710809 0.4760538 0.0691542 0.9722399 0.2235335 0.1561766 0.743377 0.6503841 0.1176801 0.8837351 0.4529501 -0.06952232 -0.9719844 -0.2245287 -0.02817773 -0.9993671 -0.02171534 0.1850803 0.5615407 0.8064846 0.1558148 0.7462021 0.6472282 0.203205 0.3470573 0.9155648 0.1848826 0.565258 0.8039292 -0.1100867 -0.8988881 -0.424124 0.2094817 0.1123242 0.9713397 -0.07465958 -0.9663851 -0.2460197 0.2032216 0.3514365 0.9138892 0.2097432 0.117133 0.9707151 -0.1177119 -0.8838615 -0.4526953 -0.1550682 -0.7491821 -0.6439566 -0.1558939 -0.7463687 -0.647017 -0.1843633 -0.5687072 -0.8016123 -0.1849483 -0.5655652 -0.8036978 -0.2028855 -0.3556988 -0.9123135 -0.1092972 -0.8433952 -0.5260595 -0.1475908 -0.6419764 -0.7523851 -0.142842 -0.7495039 -0.6464055 -0.1733145 -0.3929425 -0.9030827 0.1767892 -0.3031766 0.9363918 0.130654 0.8007811 0.5845334 -0.167299 -0.5696697 -0.8046661 0.04629379 0.9509232 0.3059444 0.1706562 -0.1226405 0.9776685 0.1300634 0.7461829 0.6529124 0.1574944 0.6252755 0.7643468 0.1547578 0.5616655 0.8127619 0.1797866 0.3909808 0.9026687 -0.1818451 -0.354252 -0.9172992 0.1600745 -0.3616877 0.9184542 0.1738587 0.3504282 0.9203116 0.1358258 -0.626417 0.7675632 0.1909066 0.05301535 0.9801755 0.1801133 0.1126509 0.9771741 -0.1831517 -0.1076767 -0.9771701 0.1326521 -0.5736905 0.8082591 -0.1859847 -0.1244177 -0.9746436 0.08159947 -0.8707204 0.4849613 -0.1681213 0.1989331 -0.9654849 0.09506678 -0.7529739 0.6511473 -0.1835979 0.118466 -0.9758369 -0.1382001 0.5380852 -0.8314837 -0.1724867 0.3545352 -0.9189957 -0.1402124 0.5696018 -0.8098731 -0.1132306 0.7326321 -0.6711402 -0.1982287 -0.9650374 -0.1714888 -0.1050564 -0.9944654 -0.001360893 0.1112824 -0.9344685 0.3382083 0.2042729 -0.8488007 0.4876577 0.4191305 -0.5857254 0.6937258 0.4876748 -0.4391105 0.7545563 -0.7027815 -0.0806303 -0.7068217 -0.683223 -0.1238377 -0.7196324 0.6916188 -0.1287184 0.7107005 -0.4117922 -0.5842627 -0.6993313 -0.4806351 -0.4365226 -0.7605511 0.9025253 0.2118676 0.3749138 0.8744069 0.1632928 0.4568895 -0.1053934 -0.9339528 -0.3415036 -0.1983579 -0.848047 -0.4913964 0.2034313 -0.9645444 0.1681362 0.1105822 -0.9938656 -0.00168842 0.4181405 -0.7879711 0.4519513 0.4866712 -0.6710447 0.5593303 -0.7056755 0.1718012 -0.6873912 -0.683157 0.1301105 -0.7185874 0.6886124 -0.3655645 0.6262394 0.731893 -0.1966264 0.6524345 -0.479915 -0.1497215 -0.8644451 -0.4111878 -0.3095527 -0.8573809 -0.1053199 -0.7607498 -0.6404433 -0.1980828 -0.628694 -0.7520021 0.1102467 -0.9334291 -0.3414028 0.2029106 -0.9640262 -0.1717 0.4173589 -0.8953214 0.1555994 0.4858099 -0.8222161 0.296563 -0.7032166 0.4404883 -0.5580829 -0.6622807 0.3775682 -0.647168 0.6899319 -0.5566205 0.4627825 0.7308066 -0.4725477 0.4925651 -0.4103314 0.00263971 -0.9119327 -0.4789898 0.1552947 -0.8639747 0.8958768 -0.1329027 0.4239596 0.9016317 -0.1148148 0.4169866 -0.1974425 -0.3334448 -0.9218629 -0.104839 -0.4957626 -0.8621069 0.1103201 -0.7604525 -0.6399542 0.2027829 -0.8473024 -0.4908745 0.4168834 -0.8948377 -0.159605 0.4851938 -0.8744042 -0.002072036 -0.665704 0.6026731 -0.4400266 -0.6457382 0.5869626 -0.4883617 0.6892157 -0.6818172 0.2451676 -0.4092925 0.3146763 -0.8564219 -0.4779584 0.441758 -0.7592139 0.8788562 -0.3289165 0.3455805 -0.1965071 0.002088069 -0.9805003 -0.1040264 -0.1709342 -0.9797755 0.203052 -0.6284615 -0.7508702 0.1107779 -0.4957944 -0.8613457 0.4848986 -0.821303 -0.3005577 0.4167596 -0.7865799 -0.4556353 -0.6131397 0.7362176 -0.2864321 -0.6473035 0.7584063 -0.07627689 -0.6296738 0.7309437 -0.2631201 -0.6186684 0.7846261 -0.04014384 0.7297009 -0.6654233 0.1573165 0.6865445 -0.7270847 -0.002152442 -0.4082068 0.5889004 -0.6975412 -0.4769421 0.6751165 -0.5628002 -0.1953904 0.3374641 -0.9208369 -0.102978 0.1745514 -0.9792484 0.203684 -0.3338951 -0.9203407 0.1115903 -0.1713792 -0.9788652 0.4849616 -0.6693261 -0.5628631 0.4170069 -0.5836144 -0.6967779 0.7292174 -0.6649341 -0.1615699 0.6884622 -0.6810592 -0.2493555 -0.4072102 0.7922469 -0.4544498 -0.4316938 0.8892119 -0.151469 -0.1770939 0.9691522 -0.1714118 -0.4760627 0.8272356 -0.2984053 -0.3879739 0.9135763 -0.1218798 0.8931006 -0.4387786 0.09922057 0.9096271 -0.394105 0.1313775 -0.1942368 0.6321874 -0.7500741 -0.1018086 0.4990167 -0.8605912 0.204624 8.6832e-4 -0.9788404 0.1126593 0.1736683 -0.9783391 0.4853745 -0.4367861 -0.7573834 0.4176062 -0.3103933 -0.8539679 0.6885238 -0.5551891 -0.4665834 0.8719503 -0.476377 -0.1129937 -0.1006603 0.7633293 -0.6381192 -0.193163 0.8507442 -0.4887968 0.1138333 0.4977285 -0.8598305 0.2057453 0.3354536 -0.9193148 0.4184666 1.09105e-4 -0.9082322 0.4860839 -0.1517608 -0.8606342 0.7292969 -0.4710478 -0.4962257 0.6866994 -0.3636202 -0.6294635 -0.09967768 0.9356158 -0.3386554 0.05321472 0.9972167 -0.05222195 -0.1993558 0.9676278 -0.1547703 0.1149764 0.7617142 -0.6376299 0.2069029 0.6294967 -0.7489494 0.4195017 0.310433 -0.8530239 0.4870146 0.1514062 -0.8601703 0.7299003 -0.1946077 -0.6552661 0.6894547 -0.1265636 -0.7131857 0.9056982 -0.3356091 -0.2589927 0.8835026 -0.3204678 -0.3416486 0.1990925 0.9618667 -0.1875492 0.1159567 0.9337745 -0.3385547 0.2800132 0.9486172 -0.1473708 0.2079644 0.8475424 -0.4882856 0.4205809 0.5831592 -0.6950088 0.4880424 0.4361289 -0.7560465 0.6902129 0.1245256 -0.712811 0.8828406 -0.137699 -0.4490339 0.4890568 0.6680505 -0.5608316 0.421571 0.7853989 -0.4532403 0.6910633 0.3603227 -0.6265773 0.7488453 0.2252365 -0.6232971 0.9009229 -0.07504886 -0.4274408 0.4333699 0.8833561 -0.1785287 0.5141116 0.8567827 -0.04016131 0.6720461 0.7395257 -0.03815555 0.489917 0.8192331 -0.2980583 0.6918991 0.5523955 -0.4649032 0.8729882 0.1647462 -0.4590757 0.7326429 0.5667787 -0.3768241 0.7162919 0.6799367 -0.1568821 0.6904638 0.679534 -0.2479788 0.8335078 0.5483372 -0.06775826 0.9017431 0.2138292 -0.3756816 0.8804405 0.3959607 -0.2608446 -0.6420123 0.7624027 0.08100908 -0.5324814 0.8070406 0.2552435 0.9076476 0.3773555 -0.1837896 0.9026624 0.4061114 -0.1423878 -0.3607221 0.8618319 0.3565466 0.9882636 0.109664 -0.1063435 0.9756019 0.1999551 0.0906589 -0.5005203 0.8133035 0.2966765 -0.3672716 0.9159525 0.1616867 -0.1765683 0.9686229 0.1749098 -0.4695143 0.6656075 0.5801062 -0.4267564 0.7825593 0.4532989 0.05337816 0.9970525 0.05511039 -0.198877 0.9671496 0.1583339 0.968957 0.1198369 0.2162442 -0.4304316 0.3295023 0.8403314 -0.4438192 0.5265315 0.7251133 -0.4148024 0.5842474 0.6975629 -0.1916693 0.8492372 0.491995 -0.09863418 0.9345764 0.3418161 0.9786635 -0.03410202 0.2026197 -0.4471003 0.06339085 0.8922349 -0.4121671 0.3112147 0.8563082 0.979913 -0.03041934 -0.1970923 -0.0987069 0.7613744 0.6407544 0.9689329 0.1189215 -0.2168565 -0.1919377 0.6298907 0.7525939 0.280465 0.9481639 0.1494146 0.1996615 0.9612905 0.189884 0.1169877 0.9327353 0.3410554 0.9884318 0.1192658 0.09369337 0.9744323 0.2047532 -0.09250855 -0.402405 -1.60374e-4 0.9154617 -0.4562891 -0.2415016 0.8564329 -0.09918063 0.4963867 0.8624173 -0.1925773 0.3346425 0.9224578 0.1169138 0.7597654 0.6395996 0.2094537 0.8460443 0.4902433 0.4322674 0.8836799 0.1795964 -0.6268308 -0.6192859 0.4728299 -0.469672 -0.4996524 0.7278432 -0.4152082 -0.3111314 0.8548682 -0.1935176 -9.0315e-4 0.9810964 -0.1000015 0.1715612 0.980085 0.2091854 0.6272044 0.7502374 0.1164468 0.4950951 0.861 0.4974873 0.8206368 0.2811791 0.9650539 -0.2066692 -0.1611179 0.4229514 0.7840145 0.4543495 0.9555151 0.04284209 -0.2918142 -0.6007019 -0.755604 0.2611894 -0.6593594 -0.745616 0.09644734 -0.5751188 -0.768675 0.2799592 -0.429753 -0.5803591 0.691734 -0.4780895 -0.674772 0.5622395 -0.101047 -0.1739308 0.9795599 -0.1946358 -0.3362678 0.9214342 0.1156463 0.1706812 0.9785162 0.2085442 0.3326417 0.9197059 0.4907615 0.6663427 0.5613738 0.4226964 0.581036 0.6955034 -0.6633993 -0.7443975 -0.07598584 -0.6070414 -0.7946702 -2.88871e-4 0.9859109 -0.05483269 0.1580291 0.6870878 0.6865478 0.237829 0.8337178 0.5481236 0.06689846 0.7184817 0.6779078 0.1556444 -0.4801985 -0.8243138 0.2998607 -0.4106512 -0.7897439 0.4557085 0.9760649 -0.2102873 0.05546694 -0.195796 -0.6309962 0.7506715 -0.1022206 -0.4984003 0.8608996 0.2076178 -0.002120852 0.9782078 0.9830552 -0.1727972 -0.06118679 0.9961502 -0.01857227 -0.08567339 0.1145741 -0.1743704 0.9779918 0.4220943 0.3078272 0.8526892 0.4903485 0.4338181 0.7558839 -0.6899752 -0.6568459 -0.3041179 -0.6395195 -0.7220926 -0.2638128 0.7337921 0.5656304 0.3763132 0.6933105 0.5509819 0.4644777 -0.4114379 -0.8976879 0.157719 -0.4808131 -0.8768229 -6.06761e-4 0.9084153 0.3760672 0.1826339 -0.196863 -0.8495481 0.4894006 -0.1033729 -0.7627074 0.6384291 0.2064892 -0.3367146 0.9186868 0.1134008 -0.4984191 0.8594875 0.489628 0.1487678 0.8591465 0.4212329 -0.002664864 0.9069486 -0.6995071 -0.501954 -0.5086572 -0.6619204 -0.5731264 -0.4831022 0.6929649 0.3584101 0.6255733 -0.4119194 -0.8972041 -0.1592085 -0.4811133 -0.8233931 -0.3009222 0.9033856 0.4046846 0.1418623 0.8813522 0.3949844 0.2592405 -0.1977066 -0.9655588 0.1691405 -0.1043528 -0.9349953 0.3389607 0.2053291 -0.6307588 0.7483203 0.1122667 -0.7623952 0.6372988 0.488708 -0.1543827 0.8586795 0.4202045 -0.3130022 0.8517381 -0.7040751 -0.3049874 -0.6412963 -0.6766675 -0.3660603 -0.6388435 0.6924021 0.1223211 0.7110674 0.750754 0.2232975 0.6216967 -0.4810527 -0.670476 -0.5648453 -0.4120433 -0.788356 -0.4568539 + + + + + + + + + + + + + + +

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

+
+
+
+ + + + 0.5359086 0.01528126 0.1469198 0.5343366 0.01781392 0.14785 0.5321867 0.01993834 0.1486349 0.529574 0.02154082 0.1492324 0.5266383 0.02253562 0.1496105 0.5235366 0.02286952 0.1497491 0.5368187 0.01247578 0.145894 0.5098838 0.01127624 0.1456416 0.5203005 0.02249389 0.1496303 0.5172531 0.02140039 0.1492491 0.5109042 0.01463514 0.1468226 0.5124139 0.01735299 0.1478032 0.5145721 0.01965284 0.1486281 0.5230546 0.05466884 0.06235593 0.5295161 0.02538615 0.1386665 0.5304027 0.02399414 0.1411253 0.5262853 0.05430591 0.06220602 0.5325711 0.0213924 0.1437286 0.5293282 0.05322682 0.0617966 0.529877 0.02619898 0.1358687 0.5317718 0.02624517 0.1321515 0.5346132 0.01829481 0.1453297 0.5361602 0.01502192 0.1460397 0.5320066 0.05149424 0.06115144 0.5336315 0.02537351 0.1292512 0.5341647 0.04920887 0.06030791 0.535165 0.02400541 0.1267542 0.5356771 0.04650354 0.0593152 0.5364141 0.02167111 0.1243951 0.536456 0.04353547 0.05823093 0.536924 0.01890748 0.1227815 0.5358793 0.005066335 0.1432031 0.5359152 0.005409121 0.142229 0.5368179 0.007933616 0.1442412 0.536456 0.04047715 0.05711811 0.5365035 0.01501548 0.1218607 0.5342513 0.002484858 0.1422728 0.5336889 0.003057897 0.1386337 0.5356771 0.03750634 0.05604141 0.5351879 0.01148605 0.1221961 0.5320247 3.33466e-4 0.1415022 0.5341647 0.03479564 0.05506348 0.533324 0.008275687 0.1233859 0.5297037 0.002375304 0.1314769 0.5315172 0.002238273 0.1352047 0.5293241 -0.00126779 0.1409345 0.5320066 0.03250259 0.054241 0.5309613 0.005238831 0.1258893 0.5263002 -0.002229392 0.1406012 0.5293282 0.03076052 0.05362188 0.5297421 0.003633439 0.1281694 0.5262853 0.02967065 0.05324214 0.5230546 0.02929627 0.05312371 0.5231218 -0.002497732 0.1405211 0.5171553 0.002243876 0.1320039 0.5199667 -0.002057731 0.1406987 0.517011 -9.33979e-4 0.1411239 0.5146553 0.002419352 0.1365574 0.5198239 0.02965921 0.05327361 0.5144198 8.10757e-4 0.141773 0.5167809 0.03073829 0.05368304 0.5171629 0.003697156 0.1280074 0.5151306 0.00620687 0.1248674 0.5126204 0.003663241 0.139761 0.5123378 0.003078997 0.1426098 0.5141025 0.03247088 0.0543282 0.5132218 0.008769571 0.12319 0.5108813 0.00574404 0.1435876 0.5108298 0.005991399 0.1428476 0.5119445 0.03475624 0.05517166 0.5116202 0.01152884 0.1221319 0.5099461 0.008957087 0.1447995 0.510432 0.03746157 0.05616438 0.5103601 0.01492774 0.1218661 0.5096532 0.04042965 0.05724865 0.5098919 0.01734572 0.122269 0.5099049 0.01928764 0.1229506 0.51057 0.01385259 0.1460184 0.5096532 0.04348796 0.05836147 0.5101986 0.02091979 0.1238654 0.5117365 0.01699817 0.1457627 0.510432 0.04645884 0.05943816 0.511222 0.02335858 0.1259837 0.5138755 0.02060204 0.1442586 0.5162159 0.02354931 0.1416947 0.5119445 0.04916948 0.06041616 0.5134227 0.02554786 0.1295108 0.5175861 0.02581197 0.1377198 0.5141025 0.05146253 0.06123858 0.5158653 0.02633213 0.1334337 0.5167809 0.05320459 0.0618577 0.5198239 0.05429446 0.0622375 0.55485 0.002903163 0.1298201 0.55485 0.002244532 0.1326556 0.50985 0.002903163 0.1298201 0.55485 0.002283632 0.1355662 0.50985 0.002244532 0.1326556 0.55485 0.00301814 0.1383831 0.50985 0.002283632 0.1355662 0.55485 0.004405438 0.1409422 0.50985 0.00301814 0.1383831 0.55485 0.006364822 0.143095 0.50985 0.004405438 0.1409422 0.55485 0.008782505 0.1447163 0.50985 0.006364822 0.143095 0.55485 0.01151788 0.1457118 0.55485 0.0144121 0.1460239 0.55485 0.01729685 0.1456342 0.50985 0.0144121 0.1460239 0.55485 0.02000457 0.1445656 0.50985 0.01729685 0.1456342 0.55485 0.02237778 0.14288 0.50985 0.02000457 0.1445656 0.55485 0.0242787 0.1406754 0.50985 0.02237778 0.14288 0.55485 0.02559673 0.1380799 0.50985 0.0242787 0.1406754 0.55485 0.02625536 0.1352444 0.50985 0.02559673 0.1380799 0.55485 0.02621632 0.1323336 0.50985 0.02625536 0.1352444 0.55485 0.02548182 0.129517 0.50985 0.02621632 0.1323336 0.55485 0.02409452 0.1269578 0.50985 0.02548182 0.129517 0.55485 0.02213513 0.1248051 0.50985 0.02409452 0.1269578 0.55485 0.01971745 0.1231838 0.50985 0.02213513 0.1248051 0.55485 0.01698207 0.1221881 0.55485 0.01408785 0.1218761 0.55485 0.01120311 0.1222656 0.50985 0.01408785 0.1218761 0.55485 0.00849539 0.1233344 0.50985 0.01120311 0.1222656 0.55485 0.006122171 0.1250201 0.50985 0.00849539 0.1233344 0.55485 0.00422126 0.1272247 0.50985 0.006122171 0.1250201 0.50985 0.00422126 0.1272247 0.5358898 -0.01317244 0.08308118 0.5347277 -0.01108139 0.08483958 0.5330154 -0.009226143 0.08640217 0.5308303 -0.007690072 0.08769863 0.5282703 -0.006542444 0.08867073 0.5254508 -0.005834698 0.08927464 0.5224985 -0.005598783 0.08948326 0.5195099 -0.005851328 0.08928221 0.5166592 -0.00658673 0.08867561 0.5140776 -0.007771015 0.08769148 0.5109148 -0.01023191 0.08563894 0.5088666 -0.01344799 0.08297002 0.5084446 -0.01634961 0.08051532 0.5221919 0.06541895 0.00482726 0.5295901 -4.92361e-4 0.08037829 0.5310667 -0.003637611 0.08259797 0.5255423 0.06511324 0.004558682 0.5327874 -0.006541609 0.0835765 0.528698 0.06420201 0.003782808 0.5301679 0.002059757 0.07677698 0.5347443 -0.01018393 0.08383637 0.5314756 0.06273812 0.002544701 0.5323479 0.003027796 0.07281738 0.5337136 0.06080669 9.16357e-4 0.5341678 0.002908825 0.06955564 0.535282 0.05852001 -0.001007616 0.535634 0.001799464 0.06627899 0.5360898 0.0560109 -0.003115415 0.5363957 -1.56291e-4 0.06345725 0.5345811 -0.02172076 0.0759148 0.5344994 -0.02083367 0.07452309 0.5358881 -0.01943302 0.07782918 0.5360898 0.05342519 -0.005284547 0.5362043 -0.003458321 0.06099486 0.5326202 -0.02371644 0.07424771 0.535282 0.05091321 -0.007388889 0.5350171 -0.007000625 0.05985176 0.5316795 -0.02093303 0.06951534 0.5301116 -0.02531212 0.07291817 0.5298362 -0.01948386 0.06570959 0.5337136 0.04862093 -0.009306252 0.5337137 -0.009723842 0.05969667 0.5271909 -0.02642136 0.07199817 0.5297153 -0.01700997 0.06264984 0.5314756 0.04668152 -0.01092511 0.5316271 -0.013345 0.06041598 0.528698 0.04520773 -0.01215136 0.5255423 0.04428523 -0.01291388 0.5240164 -0.02698421 0.07153749 0.5221919 0.0439676 -0.01316821 0.5207596 -0.0269702 0.07156109 0.5152121 -0.0192461 0.06533449 0.5153368 -0.01755714 0.06320005 0.517597 -0.02638006 0.07206761 0.5146996 -0.02524572 0.07302969 0.5142427 -0.02042943 0.06773096 0.5188415 0.04427325 -0.01289963 0.5122243 -0.02362859 0.07439523 0.5125786 -0.02102959 0.07070356 0.5156858 0.04518455 -0.0121237 0.5140091 -0.01454854 0.0609582 0.510305 -0.02161622 0.07609039 0.5104897 -0.02081161 0.07449859 0.5129082 0.04664844 -0.01088559 0.5112724 -0.009940326 0.05964744 0.5088685 -0.01918345 0.07821244 0.5106702 0.04857981 -0.009257256 0.5096649 -0.006554961 0.05991971 0.50885 -0.004141032 0.06069576 0.5091017 0.05086654 -0.007333278 0.50885 0.001044213 0.06504786 0.508294 0.05337566 -0.005225419 0.5104178 -0.009824514 0.08387696 0.508294 0.05596131 -0.003056347 0.5091017 0.05847328 -9.51981e-4 0.5096823 0.002241492 0.06733053 0.513118 -0.004956841 0.08317327 0.5106702 0.06076562 9.65346e-4 0.5113618 0.003102302 0.07073312 0.5152578 -9.48596e-4 0.08083367 0.5129082 0.06270498 0.002584159 0.5138255 0.002637565 0.07506275 0.5156858 0.06417876 0.003810465 0.515131 0.001387178 0.07793468 0.5188415 0.06510132 0.004572927 0.55785 -0.01070278 0.05979561 0.55785 -0.01354718 0.06056392 0.55785 1.34283e-4 0.07964748 0.55785 0.0017367 0.07727527 0.55785 -0.01770877 0.08011436 0.55785 -0.01943302 0.07782918 0.55785 -0.01612085 0.06199812 0.50885 6.61575e-4 0.0789929 0.50885 -0.001396298 0.08113026 0.55785 -0.01827061 0.064013 0.50885 -0.01763564 0.08018982 0.55785 0.002735614 0.07459253 0.55785 -0.01986837 0.06648844 0.55785 -0.015495 0.08192938 0.55785 -0.01291614 0.08317226 0.50885 0.002136111 0.07641822 0.55785 -0.02081906 0.06927722 0.50885 -0.01531684 0.0820409 0.55785 0.003074944 0.07174998 0.55785 -0.02106606 0.07221317 0.55785 -0.01011723 0.08377319 0.55785 -0.02059471 0.07512152 0.50885 0.00293827 0.07356166 0.55785 0.002715528 0.06882566 0.55785 -0.007255494 0.08369833 0.50885 -0.009698092 0.08380478 0.50885 -0.006737351 0.08361113 0.50885 0.00301969 0.07059574 0.50885 0.002375364 0.06769949 0.55785 -0.004491806 0.08295184 0.55785 0.001658558 0.06607544 0.55785 -0.001981496 0.08157581 0.55785 -3.29822e-5 0.06366306 0.50885 -0.003913283 0.08270126 0.55785 -0.00225836 0.06173217 0.55785 -0.004885196 0.06039768 0.55785 -0.007756948 0.05973911 0.5088495 -0.008248329 0.05962961 0.5088498 -0.01355081 0.06048887 0.50885 -0.01703369 0.06273531 0.50885 -0.01886624 0.06478852 0.5088502 -0.02069854 0.0685141 0.50885 -0.02104473 0.07260382 0.50885 -0.02053856 0.07530897 + + + + + + + + + + 0.005247235 -0.3419563 0.9397013 0.005176603 -0.3418475 0.9397413 0.005171477 -0.3419559 0.9397019 0.006405651 -0.3415651 0.9398364 0.005197823 -0.3419944 0.9396877 0.005180597 -0.3419202 0.9397148 -0.03460615 -0.3221923 0.9460415 0.005181729 -0.3419297 0.9397113 0.005660235 -0.3372228 0.9414079 0.005179166 -0.341921 0.9397144 0.005180478 -0.3419207 0.9397146 0.1156545 0.9336211 0.3390809 0.340781 0.8840528 0.3198735 0.4721717 0.8291755 0.2992019 0.1205328 0.9331486 0.3386823 0.3410713 0.8839247 0.319918 0.5878167 0.7619449 0.271867 0.5476679 0.7836729 0.2931156 0.7252361 0.6425679 0.2472633 0.5398316 0.7920541 0.285013 0.4562513 0.8370207 0.3020451 0.3546099 0.8794043 0.3176478 0.8639947 0.4685928 0.1842125 0.8868072 0.4456776 0.1222484 0.6955495 0.6762186 0.2427741 0.5680506 0.7748247 0.277426 0.9507829 0.2342375 0.2028416 0.8113238 0.5505437 0.1966101 0.7484692 0.6249655 0.2218377 0.9225495 0.363888 0.1284059 0.8854533 0.4387812 0.1531131 0.9870111 0.1523525 0.05097073 0.9709072 0.2271833 0.07567787 0.9551311 -0.2886493 -0.06637978 0.9943978 -0.09811598 -0.03932398 0.9999772 0.002286553 -0.006366372 0.8595314 -0.491196 -0.141182 0.8488464 -0.4861184 -0.2077228 0.9243825 -0.3572734 -0.1336888 0.9709098 -0.2225909 -0.08824658 0.7160782 -0.6640132 -0.2152177 0.812525 -0.5467315 -0.2022075 0.8854649 -0.4346439 -0.1644283 0.5250602 -0.8019582 -0.2849124 0.5324819 -0.7968168 -0.2855631 0.7484864 -0.6212676 -0.2319368 0.6437095 -0.7183029 -0.2639679 0.3189148 -0.8886616 -0.3295056 0.5087661 -0.808099 -0.2968723 0.5680407 -0.771916 -0.2854391 0.4708483 -0.8263954 -0.3088245 0.3313182 -0.8862603 -0.3236833 0.3546117 -0.8780095 -0.3214808 0.08761084 -0.9361116 -0.3406165 0.1205309 -0.9324806 -0.3405176 -0.3765095 -0.8729586 -0.3101358 -0.3541382 -0.8786705 -0.3201943 -0.563929 -0.777028 -0.2796636 -0.1486312 -0.9296832 -0.337043 -0.1205391 -0.9329276 -0.339288 -0.362326 -0.8763614 -0.3173495 -0.5833404 -0.7683568 -0.2633289 -0.354594 -0.879257 -0.3180729 -0.5378888 -0.7930945 -0.2857916 -0.7430607 -0.6293163 -0.227644 -0.757502 -0.6206579 -0.202422 -0.6957224 -0.6764202 -0.241715 -0.5680606 -0.7739338 -0.2798815 -0.8874258 -0.4521996 -0.08939349 -0.7484994 -0.6240335 -0.2243459 -0.8144326 -0.5469768 -0.193691 -0.9622431 -0.27116 -0.02367609 -0.8854545 -0.4377138 -0.1561317 -0.9274508 -0.3534084 -0.1222195 -0.9709405 -0.2260481 -0.07859277 -0.9999743 0.004779934 0.005367159 -0.9817948 -0.1801123 -0.06031978 -0.9575157 0.2294995 0.1746249 -0.9999935 -0.001228094 0.003428697 -0.9877007 0.1451134 0.0582205 -0.8841687 0.4110087 0.2220756 -0.9709258 0.2237269 0.0851441 -0.9476502 0.2979953 0.1147088 -0.7491232 0.6124315 0.2524721 -0.633695 0.7288119 0.2593533 -0.8312282 0.520358 0.1956714 -0.8854445 0.4356876 0.1617541 -0.5687783 0.7672502 0.2963418 -0.4851668 0.821271 0.3002117 -0.6515983 0.7113224 0.2635149 -0.7485305 0.6223771 0.228799 -0.3551477 0.8764571 0.3251047 -0.5680681 0.7728322 0.2828942 -0.4988874 0.8134552 0.2990019 -0.3545984 0.8782351 0.3208791 -0.3387928 0.8835504 0.3233548 -0.1207385 0.9326304 0.3400334 -0.1205366 0.9326607 0.3400222 0.6751872 -0.6892159 -0.2628761 0.7671375 0.6093647 0.2004364 -0.9352767 0.3507232 0.04744231 -0.8134039 0.5552195 0.1735094 -0.8797334 -0.4410094 -0.1777073 0.005067408 -0.3419054 0.9397208 0.005246937 -0.3419482 0.9397042 0.00515896 -0.341916 0.9397165 0.00518912 -0.3419957 0.9396873 0.005230367 -0.341861 0.939736 0.005189478 -0.3418755 0.939731 0.005183339 -0.3419232 0.9397137 0.00517565 -0.3419533 0.9397027 0.005201697 -0.3418849 0.9397276 -0.03762328 -0.3622543 0.9313198 0.006279468 -0.3468453 0.9379013 -0.005177736 0.3420076 -0.9396829 -0.005184173 0.3419155 -0.9397165 -0.005166411 0.3419017 -0.9397215 -0.00517863 0.3419382 -0.9397082 -0.005182623 0.3419255 -0.9397128 -0.005181312 0.3419123 -0.9397176 -0.005187749 0.3419215 -0.9397142 -0.005186796 0.3419108 -0.9397182 -0.005178987 0.3418381 -0.9397447 -0.005189895 0.3419376 -0.9397084 -0.005175232 0.3419039 -0.9397207 -0.005181431 0.3419294 -0.9397113 -0.0051831 0.3419286 -0.9397116 -0.005182683 0.3419288 -0.9397116 -0.005183041 0.341927 -0.9397123 -0.005182981 0.3419275 -0.9397121 -0.005183279 0.3419266 -0.9397124 -0.005179464 0.341916 -0.9397163 -0.005190074 0.3419486 -0.9397043 -0.005185186 0.3419502 -0.9397038 -0.005178272 0.3419302 -0.9397111 -0.005180895 0.3419308 -0.9397109 -0.005183815 0.3419348 -0.9397094 -0.005184233 0.3419117 -0.9397178 0.005539894 -0.974053 -0.2262524 0.001735806 -0.9999085 0.01342499 -0.003555715 -0.9993808 -0.03500908 -0.02027404 -0.9738679 -0.2262088 -0.001728475 -0.9723519 0.2335141 0.001170992 -0.9676418 0.2523254 0.01820427 -0.9986582 0.04848289 0.001101732 -0.9999093 0.01342523 0.003993332 -0.879127 0.476571 -0.02470976 -0.9673484 0.2522428 0.00654304 -0.7395291 0.6730929 -0.006861448 -0.8349531 0.5502783 -0.03230649 -0.8786773 0.4763219 0.004338026 -0.5569569 0.8305301 -0.004387438 -0.6223254 0.7827464 -0.1112076 -0.7349481 0.6689426 -0.008655309 -0.3420081 0.9396572 0.001515269 -0.5494189 0.8355457 -0.008673787 -0.341933 0.9396844 0.004348158 -0.1071807 0.99423 -0.001027107 -0.05740785 0.9983503 0.006539583 -0.3411214 0.9399966 0.006422877 -0.3419404 0.9396997 0.005207061 0.1338396 0.9909894 -0.08681696 -0.1214589 0.9887925 -0.004356384 0.2100462 0.9776818 0.004104495 0.3671212 0.930164 -0.04624056 0.1336922 0.9899436 -0.004980802 0.4565683 0.8896746 0.005442559 0.5790489 0.8152747 0.01451754 0.3777585 0.9257904 -0.005200505 0.3671208 0.9301588 -0.004213333 0.7055522 0.7086455 0.003202974 0.7573403 0.6530127 0.02332651 0.6455325 0.7633767 -0.02375996 0.578895 0.8150559 0.003073036 0.8916134 0.4527871 -0.001054525 0.8700542 0.4929551 -0.01778864 0.7572238 0.6529133 0.01922446 0.866044 0.4995982 0.003457367 0.9740617 0.2262564 -0.00152707 0.9603441 0.2788133 -0.003725886 0.891609 0.4527911 0.001356363 0.9999091 -0.01342469 -0.001972258 0.999933 0.0114125 0.02107435 0.9934726 0.1121085 -0.01656126 0.9739342 0.2262257 0.003201782 0.9676351 -0.2523332 -0.01679176 0.9997689 -0.0134229 -0.001269638 0.9574618 -0.2885574 0.01910561 0.9780637 -0.2074283 0.001533508 0.8773839 -0.4797866 9.48736e-4 0.8791431 -0.476557 -0.01832401 0.9674788 -0.252288 0.003613233 0.7395226 -0.6731221 -0.002224206 0.7102355 -0.7039607 -0.01707094 0.8790102 -0.4764974 0.004449069 0.5569613 -0.8305265 -0.003374457 0.5037787 -0.8638263 -0.08094263 0.7370878 -0.6709322 0.005635201 0.3420427 -0.9396675 -0.357886 0.5047395 -0.7855926 -0.007396519 0.2309768 -0.9729312 0.006253778 0.1071796 -0.99422 -0.003875911 -0.09320068 -0.9956398 0.001576304 -0.1338379 -0.991002 -0.2159326 0.119635 -0.9690515 0.06758666 -0.05282902 -0.9963139 -0.001673519 -0.3466485 -0.9379937 0.001520633 -0.3671303 -0.9301683 -0.05020344 -0.133671 -0.9897534 0.003957092 -0.5790762 -0.8152639 -0.01035839 -0.363262 -0.9316295 -0.002747654 -0.3671497 -0.9301579 0.004243791 -0.757337 -0.6530106 -0.004702448 -0.6338785 -0.7734184 0.00823301 -0.5433612 -0.8394587 -0.01427412 -0.5790221 -0.8151869 -0.002569437 -0.8170229 -0.5765997 0.003835082 -0.8916035 -0.4528009 0.01159477 -0.7774205 -0.6288744 -0.006726622 -0.7573296 -0.6529982 -0.003808677 -0.9346395 -0.3555763 -0.01543265 -0.8915039 -0.4527502 0.01732879 -0.9396609 -0.341668 0.02794939 -0.9257099 0.3772003 0.05574589 -0.7812908 0.6216729 0.05480575 0.06069201 0.9966509 0.05523294 0.8325384 -0.551207 0.1042714 0.6268948 -0.7720948 1 -1.14816e-4 0 1 7.80535e-5 0 1 1.14824e-4 0 1 0 0 1 -1.14822e-4 0 1 5.7402e-5 0 1 -8.28133e-6 0 1 3.20028e-5 0 1 -7.66937e-6 0 1 1.97819e-5 0 1 -4.01953e-5 0 1 7.80549e-5 0 1 -1.37445e-5 0 1 -5.47226e-6 0 1 5.74152e-5 0 1 5.1542e-6 0 1 3.64818e-6 0 1 -2.29631e-4 0 1 5.99972e-5 0 1 -1.36347e-5 0 -1 1.14816e-4 0 -1 -7.80533e-5 0 -0.9721182 -0.1025974 0.2108554 -1 0 0 -1 4.00036e-6 0 -1 -9.57545e-6 0 -1 3.90229e-5 0 -0.9999136 0.01236277 0.004484057 -1 2.70652e-6 0 -0.9956243 0.03674507 -0.08591943 -0.9999803 0.004764318 0.004099965 -0.9999685 -0.006014287 -0.005178868 -0.999935 -0.01017588 -0.005153656 -1 7.80547e-5 0 -0.9999989 -0.001131415 0.001031398 0.002754628 -0.6427094 0.7661051 0.002779006 -0.642733 0.7660852 0.002770662 -0.6426776 0.7661317 0.002770423 -0.6427034 0.7661102 0.002776026 -0.6427121 0.7661028 0.002784132 -0.6426637 0.7661435 0.003362655 -0.6398748 0.7684718 0.002775847 -0.6426466 0.7661577 0.002792298 -0.6426787 0.7661308 0.002692461 -0.6425508 0.7662384 -0.0865817 -0.6359874 0.7668271 0.1060385 0.7619957 0.6388415 0.5065441 0.6561619 0.5593431 0.557433 0.6372504 0.5321471 0.3133509 0.7278711 0.6099303 0.1205335 0.7610061 0.6374492 0.6750363 0.5613212 0.4787948 0.6770045 0.5606508 0.4767974 0.5184048 0.6562943 0.5482102 0.4588973 0.6814017 0.5701798 0.3546039 0.7173939 0.5996684 0.8166747 0.42328 0.3922713 0.6362208 0.5917969 0.4949742 0.5680546 0.6322732 0.5268252 0.9199755 0.2844197 0.2697233 0.7675685 0.4924334 0.4103024 0.7485062 0.5099065 0.4239503 0.8952394 0.3429758 0.2844539 0.8854491 0.3581109 0.2962037 0.9743834 0.1740872 0.1423757 0.9709293 0.1855 0.1512817 0.915925 -0.3118851 -0.2526047 0.9989129 -0.03450632 -0.03134244 0.999994 0.002230286 -0.002690494 0.7978545 -0.4860184 -0.3566712 0.9453531 -0.2488799 -0.2106331 0.9709354 -0.1807767 -0.1568579 0.6376555 -0.6018741 -0.4807735 0.5908069 -0.6162133 -0.520796 0.8854365 -0.3538882 -0.3012729 0.858262 -0.3918911 -0.3313726 0.4413242 -0.6891775 -0.5746889 0.4424832 -0.6890253 -0.5739799 0.740993 -0.5130471 -0.4332575 0.7485251 -0.5063505 -0.4281582 0.5793522 -0.6227697 -0.5258413 0.5680604 -0.629135 -0.5305625 0.427084 -0.6922997 -0.5816532 0.3546013 -0.715126 -0.6023726 0.2233151 -0.746919 -0.6262925 -0.00794959 -0.7666542 -0.6420111 0.1205336 -0.7597241 -0.6389766 -0.4475485 -0.6883572 -0.5708457 -0.4566567 -0.6865909 -0.5657364 -0.5443373 -0.6436482 -0.5379721 -0.2387736 -0.7449467 -0.62293 -0.1205363 -0.7601689 -0.6384468 -0.6441479 -0.5949789 -0.4807013 -0.6498267 -0.5895115 -0.4797931 -0.547384 -0.6417628 -0.5371326 -0.431963 -0.6919944 -0.5784045 -0.3546087 -0.7163696 -0.6008887 -0.8067495 -0.4843896 -0.338411 -0.7028384 -0.5467981 -0.4550055 -0.5680614 -0.63079 -0.5285927 -0.9136227 -0.3102077 -0.2628017 -0.8656269 -0.3853391 -0.3196936 -0.7485162 -0.5086399 -0.4254517 -0.9933249 -0.08803206 -0.07453751 -0.8854532 -0.357059 -0.2974584 -0.9451209 -0.2523385 -0.2075375 -0.9938862 0.08541303 0.06996309 -0.9897818 -0.1114745 -0.08891302 -0.9709341 -0.1843605 -0.1526377 -0.8965928 0.3030239 0.322952 -0.9897848 0.1069197 0.09430956 -0.9999991 -8.5905e-4 0.001043856 -0.9709357 0.1823889 0.154979 -0.9445345 0.2495272 0.2135202 -0.7113681 0.5187445 0.4741939 -0.8854598 0.3549932 0.2999012 -0.8621434 0.386309 0.3278325 -0.5122033 0.6513471 0.5598167 -0.7485107 0.5074765 0.4268483 -0.7036769 0.5426567 0.4586531 -0.4652286 0.6772004 0.5700545 -0.5680679 0.6301077 0.5293989 -0.5258569 0.6510581 0.5473554 -0.5635009 0.6324464 0.5314869 -0.3546011 0.716117 0.6011942 -0.3171191 0.7258054 0.6104443 -0.1205383 0.7605493 0.6379932 -0.1073602 0.761496 0.6392166 0.7754644 -0.4646931 -0.427452 0.8064497 0.4598065 0.3717756 -0.7850223 -0.4685603 -0.4052054 -0.8006926 0.4933112 0.3399051 -0.5974889 0.6175282 0.5115329 0.002779066 -0.6427058 0.766108 0.00275731 -0.6426668 0.7661408 0.002772986 -0.6426796 0.7661302 0.002775311 -0.6427042 0.7661095 0.002771973 -0.6426724 0.7661362 0.002773284 -0.6426962 0.7661162 0.002755343 -0.6426692 0.7661389 0.002775073 -0.6426954 0.7661169 0.002775967 -0.6426962 0.7661162 0.004649758 -0.6557708 0.7549457 -0.002774834 0.6426698 -0.7661383 -0.00277251 0.6427018 -0.7661115 -0.002769052 0.6426988 -0.766114 -0.002776563 0.642701 -0.7661122 -0.002778291 0.6426764 -0.7661327 -0.002774596 0.6427167 -0.7660991 -0.002769231 0.6425852 -0.7662093 -0.002777218 0.6426895 -0.7661218 -0.00277388 0.6426842 -0.7661262 -0.002773165 0.6426988 -0.7661139 -0.002773404 0.6426991 -0.7661138 -0.002781271 0.6426539 -0.7661516 -0.002774596 0.6426951 -0.766117 -0.002776682 0.6426953 -0.766117 -0.002774715 0.6426949 -0.7661172 -0.002776026 0.6426928 -0.766119 -0.002774834 0.6426915 -0.7661201 -0.002774894 0.6426987 -0.7661141 -0.002777934 0.6427436 -0.7660763 -0.002775847 0.6426943 -0.7661178 -0.002774834 0.6426975 -0.7661151 -0.002774953 0.642694 -0.7661181 -0.002774775 0.6426954 -0.7661169 -0.002784609 0.6426591 -0.7661473 0.003433883 -0.2607458 -0.9654015 -0.003152966 0.8161334 0.5778549 -0.003793001 -0.1927359 -0.9812434 -4.05456e-4 0.8286572 0.5597563 0 -0.7982501 0.6023261 0.001173377 -0.4867888 -0.873519 -0.003391623 -0.5191682 -0.8546655 0.01563262 0.7789314 0.6269145 -0.01822811 0.7202516 0.6934735 0.004709184 -0.683839 -0.7296178 -2.59266e-4 -0.7970517 0.6039111 0.00465548 0.9371297 0.3489502 0.003544211 -0.8401855 -0.5422877 0.001468122 -0.7874456 0.6163824 2.44618e-4 -0.6340277 0.7733104 -0.004390597 -0.777702 -0.628618 0.001330018 -0.4341648 0.9008325 0.01457643 0.919179 0.3935702 -0.01652121 0.8676454 0.496909 0.001186072 -0.9465098 -0.3226732 -0.005205631 0.9720324 0.2347891 -4.89653e-4 -0.6238768 0.7815227 -0.002975523 -0.9350113 -0.3546054 4.38802e-4 -0.4409501 0.8975316 0.003125727 0.9929447 0.1185381 -0.001157164 -0.2454143 0.9694176 0.003577172 -0.9964729 -0.08383959 0.003279268 -0.2099053 0.9777162 8.54632e-4 -0.4451785 0.8954414 0.006001353 -0.9871023 0.1599789 -0.007565617 -0.9996811 0.02409642 -0.02337014 0.962495 0.2702914 0.004340827 0.9925206 -0.1220004 -7.00955e-4 -0.9189897 0.394281 -0.00345391 0.9992572 -0.03838402 0.0337243 0.9955778 0.08767908 0.002658903 0.02615618 0.9996544 0 -0.9207769 0.39009 0.05457514 0.113152 0.9920778 0.03849458 0.9640573 -0.2628909 -0.06234526 -0.2171376 0.974148 -0.03436255 0.9990334 0.02741521 -0.002865493 0.06963628 0.9975684 0.002735197 0.2607482 0.965403 0.002634644 0.9334345 -0.3587383 -0.002182722 0.9468891 -0.3215531 -0.002382874 0.3180423 0.9480736 -0.04063975 0.06521773 0.9970432 -0.02023214 0.9759362 -0.2171154 0.003744959 0.4806773 0.8768897 8.02511e-4 0.8187693 -0.5741223 -5.42691e-6 0.8218825 -0.5696572 -0.03026378 0.3064973 0.9513903 0.003479778 0.655352 -0.7553156 -0.004348993 0.5752282 0.8179814 -0.05508768 0.892347 -0.4479758 0.004176616 0.6735939 0.7390899 -0.005849361 0.5980048 -0.8014713 0.02470421 0.4940742 0.8690687 0.005260705 0.4529166 -0.8915374 0.002595245 0.2235242 -0.974695 -0.005876123 0.3088762 -0.9510841 0.002264022 0.5294908 0.8483127 0.003322303 -0.01918309 -0.9998105 -0.002994179 0.05829143 -0.9982951 -0.1746932 0.2474102 -0.9530323 0.09388369 0.1240333 -0.9878268 0.0392906 -0.2517114 -0.9670045 -0.10388 -0.159107 -0.9817811 0.009597182 -0.5947429 -0.8038587 -0.02835953 -0.5418158 -0.8400186 0.006402969 -0.7843626 -0.6202695 -0.01496934 -0.8941175 -0.4475823 -0.01249688 -0.7460075 -0.6658204 -0.01931726 -0.8971825 -0.4412376 0.02200233 -0.9823054 -0.1859896 0.04613411 -0.9955175 0.08256369 -0.03890305 -0.9956814 -0.08429354 -0.07259142 -0.9803475 0.1834372 0.05785608 -0.90479 0.4219096 1 2.76874e-5 0 1 6.60529e-6 0 1 -1.08117e-5 0 1 -1.10749e-4 0 1 7.53266e-5 0 1 -5.1246e-6 0 1 3.01741e-5 0 1 -1.02039e-5 0 1 4.28943e-6 0 1 9.48582e-6 0 1 -3.1487e-5 0 -0.9999997 -1.27022e-4 9.44097e-4 -0.9999995 1.25375e-4 0.001090943 -0.9999989 7.97044e-4 0.001303493 -0.9999979 0.00151658 0.001413881 -0.9999949 0.002863764 0.001443445 -0.9999679 0.007993042 6.34739e-4 -0.9997313 0.02278739 -0.0042575 -0.9992858 0.02357918 -0.02952843 -0.9994424 0.02106118 -0.02591007 -0.9999998 -7.17717e-4 3.55401e-4 -0.9999997 -8.53235e-4 1.9248e-4 -0.9999995 -0.001031875 -2.82951e-5 -0.999881 -9.96423e-4 -0.01539427 -0.9999993 -0.001221597 -3.39783e-4 -0.9999806 -0.00191909 -0.005932569 -0.9999987 -0.001406311 -8.04953e-4 -0.999994 -0.001839458 -0.002926409 -0.9999975 -0.001610577 -0.001557409 + + + + + + + + + + + + + + +

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

+
+
+
+ + + + 0.268 -0.01749998 -0.239 0.292 -0.01749998 -0.239 0.292 -0.01679182 -0.2449158 0.268 -0.01607519 -0.2473219 0.292 -0.01300644 -0.2522886 0.268 -0.01052051 -0.2549283 0.268 -0.002433896 -0.2597575 0.292 -0.005229175 -0.2586746 0.268 0.007615566 -0.2602776 0.292 0.006510496 -0.2605863 0.268 0.01505792 -0.2575345 0.292 0.01566278 -0.25716 0.268 0.02100646 -0.2522886 0.292 0.0214352 -0.2517209 0.268 0.02479183 -0.2449157 0.292 0.02473074 -0.2448984 0.292 0.02549999 -0.239 0.268 0.02549999 -0.239 0.268 -0.02899998 -0.2695 0.268 -0.02899998 -0.239 0.268 0.037 -0.2695 0.268 0.037 -0.239 0.292 0.037 -0.2695 0.292 0.037 -0.239 0.292 -0.02899998 -0.239 0.292 -0.02899998 -0.2695 0.283177 0.02790576 -0.239 0.2829383 0.03087145 -0.2695 0.2831035 0.03028798 -0.239 0.2791601 0.03240793 -0.2695 0.2775248 0.03135204 -0.239 0.2808278 0.03235846 -0.239 0.2768231 0.0300942 -0.2695 0.2766535 0.02869814 -0.239 0.2768965 0.02771192 -0.2695 0.2776951 0.02655494 -0.239 0.2791723 0.02564144 -0.2695 0.28084 0.02559202 -0.239 0.2827917 0.02691614 -0.2695 0.2829383 -0.0191285 -0.2695 0.2827917 -0.0230838 -0.2695 0.2791601 -0.01759201 -0.2695 0.2768231 -0.01990574 -0.2695 0.2768965 -0.02228802 -0.2695 0.2791723 -0.02435851 -0.2695 0.283177 -0.02209419 -0.239 0.2831035 -0.01971197 -0.239 0.2775248 -0.0186479 -0.239 0.2808278 -0.01764148 -0.239 0.2766535 -0.0213018 -0.239 0.2776951 -0.02344501 -0.239 0.28084 -0.02440798 -0.239 0.328 -0.01749998 -0.239 0.352 -0.01749998 -0.239 0.352 -0.01679182 -0.2449158 0.328 -0.01607519 -0.2473219 0.352 -0.01300644 -0.2522886 0.328 -0.01052051 -0.2549283 0.328 -0.002433896 -0.2597575 0.352 -0.005229175 -0.2586746 0.328 0.007615566 -0.2602776 0.352 0.006510496 -0.2605863 0.328 0.01505792 -0.2575345 0.352 0.01566278 -0.25716 0.328 0.02100646 -0.2522886 0.352 0.0214352 -0.2517209 0.328 0.02479183 -0.2449157 0.352 0.02473074 -0.2448984 0.352 0.02549999 -0.239 0.328 0.02549999 -0.239 0.328 -0.02899998 -0.2695 0.328 -0.02899998 -0.239 0.328 0.037 -0.2695 0.328 0.037 -0.239 0.352 0.037 -0.239 0.352 0.037 -0.2695 0.352 -0.02899998 -0.239 0.352 -0.02899998 -0.2695 0.3430769 0.03048032 -0.2695 0.3427917 0.03108376 -0.239 0.3387818 0.03221237 -0.2695 0.3391723 0.03235852 -0.239 0.3412449 0.03207921 -0.2695 0.3368231 0.0300942 -0.2695 0.3368966 0.03028804 -0.239 0.3368966 0.02771192 -0.2695 0.3368231 0.0279057 -0.239 0.3391723 0.02564144 -0.2695 0.3387818 0.02578753 -0.239 0.3427579 0.02673876 -0.239 0.3427917 0.0269162 -0.2695 0.3430769 -0.01951962 -0.2695 0.3427917 -0.02308374 -0.2695 0.341245 -0.01792073 -0.2695 0.3387818 -0.01778757 -0.2695 0.3368231 -0.01990574 -0.2695 0.3368966 -0.02228802 -0.2695 0.3391723 -0.02435851 -0.2695 0.3430769 -0.0224803 -0.239 0.3427917 -0.01891618 -0.239 0.3391723 -0.01764148 -0.239 0.3368966 -0.01971191 -0.239 0.3368231 -0.02209424 -0.239 0.3387818 -0.02421241 -0.239 0.341245 -0.02407926 -0.239 + + + + + + + + + + 0 0.9929113 0.1188578 0.0125119 0.985581 0.1687413 -0.01922285 0.8894361 0.4566552 0.01878082 0.8074435 0.5896459 0.02097111 0.5126061 0.8583678 -0.0192694 0.6344765 0.7727019 0.01522064 0.05167627 0.998548 -0.02580738 0.1606673 0.9866712 -0.003854811 -0.3458312 0.9382889 -0.005777418 -0.3505954 0.9365093 0.004966855 -0.6614158 0.7500031 -0.00496596 -0.6857761 0.7277957 0.005087792 -0.8895893 0.456733 -0.002606213 -0.9004479 0.4349563 -0.002616584 -0.9916 0.1293159 0 -0.9929114 0.1188572 -1 0 0 -1 2.24875e-6 0 -1 7.80054e-7 0 -1 -2.49974e-6 0 -1 -2.50121e-6 0 0 1 0 1 0 0 1 2.69906e-6 0 1 -1.25146e-6 0 1 2.48633e-6 0 1 -1.24438e-6 0 0 -1 0 -0.999249 0.03702843 0.0114206 -0.9995124 -0.03085041 0.004824638 0.2914291 -0.9564327 -0.01748639 -0.672951 -0.7396125 -0.01050412 0.7035045 -0.7105699 0.0131185 -0.3766449 -0.9261609 0.01909279 0.9500671 -0.3119161 -0.008994996 0.9995006 0.03082376 0.006968379 0.8993846 0.4371028 -0.006966352 0.6729283 0.7396341 0.01043844 0.2927488 0.9560801 -0.01445716 -0.3321221 0.9430309 0.0196895 -0.7034973 0.7105568 -0.01416826 4.67159e-6 0 -1 0 0 -1 -8.90779e-6 0 -1 -9.2202e-6 0 -1 1.71649e-5 0 -1 6.91008e-6 0 -1 -7.99662e-7 0 -1 6.36966e-6 0 -1 -5.67562e-6 0 -1 -4.38975e-6 0 -1 -0.999249 0.03702843 0.01142066 -0.9995124 -0.03085041 0.004824638 0.2914283 -0.9564328 -0.01748639 -0.672951 -0.7396125 -0.01050406 0.7035042 -0.7105701 0.01311862 -0.3766437 -0.9261614 0.01909285 0.950067 -0.3119165 -0.008994877 0.9995006 0.03082382 0.006968379 0.8993849 0.4371021 -0.006966412 0.6729276 0.7396348 0.01043856 0.2927482 0.9560803 -0.01445698 -0.3321209 0.9430313 0.0196895 0 -1.4458e-6 1 0 0 1 -5.45115e-6 0 1 -3.18483e-6 9.5269e-7 1 3.80714e-6 -3.67907e-6 1 2.21509e-6 -4.94083e-7 1 0 5.8426e-7 1 0 1.74824e-6 1 0 3.24501e-6 1 0 -1.05323e-4 1 -3.45503e-6 -1.00639e-6 1 -2.27573e-6 0 1 0 0 1 0 1.33748e-6 1 8.24426e-6 -1.74277e-6 1 0 -4.29933e-7 1 0 -3.21043e-6 1 0 7.09439e-7 1 0 3.7035e-6 1 0 1.61931e-4 1 0 0.9929113 0.1188575 0.01251196 0.985581 0.1687417 0.02097111 0.5126053 0.8583682 0.01522064 0.05167639 0.998548 -0.02580738 0.1606669 0.9866712 -0.003854811 -0.3458307 0.938289 -0.005777418 -0.3505949 0.9365094 0.004966855 -0.6614159 0.7500029 0.005087792 -0.8895896 0.4567325 -0.002616584 -0.9916 0.1293161 0 -0.9929115 0.118857 -1 -1.56011e-6 0 -1 5.00243e-6 0 1 -2.54367e-6 0 1 1.24317e-6 0 1 -2.82594e-6 0 1 1.24438e-6 0 -0.9968137 0.079764 -6.38515e-4 -0.9999247 0.007757902 -0.009503006 -0.6575421 -0.753367 0.008756875 0.7341919 -0.6789373 0.002544641 0.6729614 -0.7396602 -0.005071759 -0.05398118 -0.9985271 0.00547415 -0.3321533 -0.9431225 -0.01393753 0.9995224 0.03082406 0.002212405 0.9995232 -0.03079843 -0.002213418 0.6729608 0.7396609 0.005071759 0.7342013 0.6789271 -0.002545297 -0.2326532 0.9725299 -0.007636725 -0.3321825 0.9432013 0.005120456 5.53487e-6 0 -1 -1.41405e-5 0 -1 5.36775e-6 0 -1 3.45509e-6 0 -1 3.61366e-6 0 -1 -4.38974e-6 0 -1 -1.44471e-5 0 -1 -0.9967839 0.07976162 0.007742106 -0.9967839 -0.07976162 -0.007742106 -0.6575531 -0.7533573 0.008756756 0.7341926 -0.6789366 0.002544641 0.6729614 -0.7396602 -0.005071878 -0.05398297 -0.9985269 0.005473971 -0.3321528 -0.9431226 -0.01393765 0.9995224 0.03082406 0.002212405 0.9995232 -0.03079849 -0.002213418 0.6729601 0.7396614 0.00507164 0.7342013 0.6789271 -0.002545356 -0.0539813 0.998527 -0.00547409 -0.3321534 0.9431225 0.01393777 -0.6575521 0.7533583 -0.008756756 -4.31447e-6 -3.19815e-6 1 -3.504e-6 -1.27919e-7 1 -6.66233e-6 1.04146e-6 1 3.75802e-6 2.70822e-6 1 6.20456e-7 -1.44582e-6 1 0 0 1 0 9.05985e-7 1 0 3.11247e-6 1 -1.06092e-6 4.31956e-6 1 0 -1.62687e-6 1 -2.19869e-6 0 1 0 0 1 0 -1.0064e-6 1 0 -3.21044e-6 1 0 0 1 0 1.24723e-6 1 0 5.18159e-5 1 + + + + + + + + + + + + + + +

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

+
+
+
+
+ + + + + 0.6859207 -0.3240135 0.6515582 7.481132 0.7276763 0.3054208 -0.6141704 -6.50764 0 0.8953956 0.4452714 5.343665 0 0 0 1 + + + + -0.2908646 -0.7711008 0.5663932 4.076245 0.9551712 -0.1998834 0.2183912 1.005454 -0.05518906 0.6045247 0.7946723 5.903862 0 0 0 1 + + + + 1 0 0 0 0 1 0 0 0 0 1 0 0 0 0 1 + + + + + + + + + + 1 0 0 0 0 1 0 0 0 0 1 0 0 0 0 1 + + + + + + + + + + 1 0 0 0 0 1 0 0 0 0 1 0 0 0 0 1 + + + + + + + + + + 1 0 0 0 0 1 0 0 0 0 1 0 0 0 0 1 + + + + + + + + + + 1 0 0 0 0 1 0 0 0 0 1 0 0 0 0 1 + + + + + + + + + + 1 0 0 0 0 1 0 0 0 0 1 0 0 0 0 1 + + + + + + + + + + + + + +
\ No newline at end of file diff --git a/kuka_kr5_support/meshes/kr5_arc/visual/link_3.dae b/kuka_kr5_support/meshes/kr5_arc/visual/link_3.dae new file mode 100644 index 000000000..cfef78625 --- /dev/null +++ b/kuka_kr5_support/meshes/kr5_arc/visual/link_3.dae @@ -0,0 +1,423 @@ + + + + + Blender User + Blender 2.79.0 commit date:2017-09-11, commit time:10:43, hash:5bd8ac9abfa + + 2017-11-10T20:06:05 + 2017-11-10T20:06:05 + + Z_UP + + + + + + + 49.13434 + 1.777778 + 0.1 + 100 + + + + + + 0 + 0 + 0 + + + + + + + + + 1 1 1 + 1 + 0 + 0.00111109 + + + + + 0 + 0 + 8192 + 1 + 1 + 1 + 1 + 0 + 0 + 0 + 1 + 29.99998 + 75 + 0.15 + 1 + 0 + 1 + 2 + 1.000799 + 30.002 + 1 + 3 + 0.04999995 + 2880 + 3 + 1 + 0 + 0 + 2 + 1 + 1 + 1 + 0 + 1 + 0.1 + 0.1 + 1 + 0.000999987 + 1 + 0 + 0 + 1 + 1 + 1 + 1 + 1 + 1 + 1 + 2 + 1 + 1 + 1 + 1 + 0 + + + + + + + + + + + + 0 0 0 1 + + + 0 0 0 1 + + + 1 0.4980392 0 1 + + + 0.5 0.5 0.5 1 + + + 0 + + + 1 1 1 1 + + + 1 + + + + + + + + + + + 0 0 0 1 + + + 0 0 0 1 + + + 0 0 0 1 + + + 0.5 0.5 0.5 1 + + + 0 + + + 1 1 1 1 + + + 1 + + + + + + + + + + + 0 0 0 1 + + + 0 0 0 1 + + + 0.09803922 0.09803922 0.09803922 1 + + + 0.5 0.5 0.5 1 + + + 0 + + + 1 1 1 1 + + + 1 + + + + + + + + + + + 0 0 0 1 + + + 0 0 0 1 + + + 0.09803922 0.09803922 0.09803922 1 + + + 0.5 0.5 0.5 1 + + + 0 + + + 1 1 1 1 + + + 1 + + + + + + + + + + + + + + + + + + + + + + + + + -0.0245307 -0.0521304 -0.02899998 -0.03156256 -0.04817026 -0.02899998 0.03157514 -0.04816162 -0.02899998 0.0245307 -0.0521304 -0.02899998 -0.01372969 -0.05606001 -0.02899998 6.43153e-4 -0.05771321 -0.02899998 0.01434463 -0.05586892 -0.02899998 0.05493241 0.01784855 -0.02899998 0.04825359 0.03148859 -0.02899998 0.05756723 0.003621816 -0.02899998 0.04820424 -0.03157109 -0.02899998 0.05356782 -0.021209 -0.02899998 0.05681151 -0.01018255 -0.02899998 -0.0206477 0.05389714 -0.02899998 -0.03157174 0.04818171 -0.02899998 0.03159308 0.04816758 -0.02899998 0.02123379 0.05363047 -0.02899998 -0.007229328 0.05722624 -0.02899998 0.007239162 0.0573039 -0.02899998 -0.04831957 -0.03152406 -0.02899998 -0.04815262 0.03143435 -0.02899998 -0.05194664 0.02515506 -0.02899998 -0.05673629 0.01082301 -0.02899998 -0.05756723 -0.003621816 -0.02899998 -0.05508732 -0.01722264 -0.02899998 -0.04831159 0.03152173 -0.03899997 -0.04808956 0.03165346 -0.03099995 -0.04867613 -0.03089076 -0.03899997 -0.04810059 -0.03171402 -0.03099995 -0.03953897 -0.04210478 -0.03899997 -0.03087091 -0.04864484 -0.03899997 -0.03154838 -0.04815262 -0.03099995 -0.03948533 -0.04204767 -0.03099995 0.03087091 -0.04864484 -0.03899997 0.03903853 -0.04251146 -0.03899997 0.03154838 -0.04815262 -0.03099995 0.03997623 -0.04163086 -0.03099995 0.04874026 -0.03093147 -0.03899997 0.04808956 -0.03165346 -0.03099995 0.04874026 0.03093147 -0.03899997 0.04812043 0.03160732 -0.03099995 0.03903853 0.04251146 -0.03899997 0.02782565 0.05061495 -0.03899997 0.03154838 0.04815262 -0.03099995 0.03997623 0.04163086 -0.03099995 -0.03087091 0.04864484 -0.03899997 -0.03903853 0.04251146 -0.03899997 -0.03154838 0.04815262 -0.03099995 -0.03997623 0.04163086 -0.03099995 -0.09399998 -0.09056699 -0.128333 -0.09399998 -0.07818245 -0.1371601 -0.09399914 -0.09566742 -0.1384754 -0.09399998 -0.08406698 -0.121833 -0.09399998 -0.07627439 -0.1069558 -0.09398972 -0.1121742 -0.1395047 -0.09399998 -0.07490116 -0.103232 -0.09400016 -0.1137031 -0.1389688 -0.09399998 -0.1217432 -0.1399126 -0.09399998 -0.1305366 -0.1385344 -0.09399992 -0.1379855 -0.1361324 -0.09399998 -0.149433 -0.128333 -0.09399998 -0.08406698 -0.062967 -0.09399998 -0.06942564 -0.05143684 -0.09399998 -0.07234191 -0.08816009 -0.09399998 -0.1531754 -0.1260724 -0.09399998 -0.07642143 -0.04507851 -0.09399998 -0.07342141 -0.04207855 -0.09399998 -0.155933 -0.121833 -0.09399998 -0.09056699 -0.05646699 -0.09399998 -0.1611087 -0.1158407 -0.09399998 -0.06807649 -0.01357322 -0.09399998 -0.1647949 -0.1077172 -0.09399992 -0.1670137 -0.09748607 -0.09399998 -0.155933 -0.062967 -0.09399998 -0.1692067 -0.06836462 -0.0940001 -0.1698155 -0.0538451 -0.09399998 -0.07342141 0.04207855 -0.0940001 -0.06936252 0.04899185 -0.0940001 -0.0683934 0.02955412 -0.09399998 -0.1635786 -0.04507851 -0.09399998 -0.149433 -0.05646699 -0.09399998 -0.07642143 0.04507851 -0.09399998 -0.1665786 -0.04207855 -0.09399998 -0.1711718 -0.03036153 -0.09399998 -0.1665786 0.04207855 -0.09399974 -0.1711179 0.03169071 -0.09399998 -0.1635786 0.04507851 -0.09400004 -0.1707242 0.04899311 -0.09399998 -0.1710746 0.01167112 -0.09399998 -0.1715521 0.001659095 -0.09399998 -0.1715098 -0.01844203 -0.07499998 -0.0955426 0.1306424 -0.07499998 -0.09191042 0.128333 -0.07499998 -0.1056276 0.1352719 -0.07499998 -0.1153326 0.1375851 -0.07499998 -0.130309 0.1361878 -0.07499998 -0.1221557 0.1375827 -0.07500302 -0.140515 0.132726 -0.07499998 -0.1469902 0.128333 -0.07499998 -0.1629256 0.109443 -0.07499998 -0.155933 0.062967 -0.07499998 -0.08406698 0.062967 -0.07499998 -0.07020932 0.06446516 -0.07499992 -0.06963264 0.05200046 -0.07499998 -0.09056699 0.05646699 -0.07499992 -0.07312667 0.09133237 -0.07499849 -0.1560251 0.1202326 -0.07499927 -0.08399343 0.1210776 -0.07499998 -0.07456618 0.1025128 -0.07499998 -0.07759803 0.1110543 -0.07499998 -0.149433 0.05646699 -0.0749998 -0.1706856 0.05200165 -0.07499998 -0.1706044 0.07145994 -0.07500004 -0.1671898 0.09338903 0.3189872 -0.1487599 0.05696123 0.351 -0.153026 0.05719834 0.351 -0.1468712 0.06033521 0.2773853 -0.1488766 0.04989469 0.2742962 -0.1406487 0.05340307 0.2328689 -0.1382394 0.04835879 0.2302891 -0.1453373 0.04467797 0.2039088 -0.1370694 0.04785102 0.2010488 -0.1440678 0.0444411 0.1749873 -0.1368831 0.05068892 0.1710694 -0.1438451 0.0475254 0.144698 -0.1376848 0.05710536 0.1392657 -0.144736 0.05421364 0.1046741 -0.1422013 0.06835591 0.09882032 -0.1471758 0.06661337 0.0259999 -0.1480501 0.09753918 0.01305031 -0.1577898 0.09092414 -0.01541548 -0.1508687 0.1109547 -0.03008186 -0.1606668 0.102624 -0.04486757 -0.1524581 0.1184127 -0.05534052 -0.1579914 0.1135443 -0.074 -0.155933 0.1199516 -0.074 -0.1535121 0.1233166 0.3196638 -0.1368051 0.06162291 0.351 -0.1404132 0.06281429 0.1087571 -0.1367375 0.06979751 0.0367273 -0.1409335 0.09795099 -0.009563028 -0.1389151 0.1172319 -0.0416752 -0.1400002 0.1264406 -0.074 -0.1468104 0.128333 0.3203199 -0.09988677 0.060579 0.351 -0.1029092 0.06378787 0.351 -0.09313666 0.06033885 0.319114 -0.09404039 0.05823689 0.233902 -0.09951776 0.04733377 0.23427 -0.1042044 0.04926949 0.2052569 -0.105077 0.04849016 0.2034643 -0.09809738 0.0455414 0.1766777 -0.1053058 0.05118829 0.1742813 -0.09846991 0.04845041 0.1470623 -0.1048872 0.05752199 0.1443145 -0.09725397 0.05444443 0.1079142 -0.1003416 0.06897211 0.0402919 -0.1000503 0.09740352 0.03180932 -0.09358966 0.09711885 -0.008280158 -0.09768187 0.1150543 -0.01186418 -0.09099429 0.1121458 -0.04179638 -0.09638196 0.1245649 -0.04308688 -0.0895158 0.1205669 -0.074 -0.09211951 0.128333 -0.074 -0.08854246 0.1260589 0.351 -0.08697164 0.05719757 0.3190924 -0.08810389 0.05520927 0.2340834 -0.09430021 0.04473096 0.1045051 -0.09363281 0.06549394 0.02576696 -0.08831578 0.09445708 -0.0131812 -0.08502316 0.1059704 -0.04560834 -0.08426499 0.115272 -0.074 -0.08406698 0.1208518 -0.04921936 -0.03910708 -0.115 -0.05155104 -0.05806797 -0.115 -0.06068927 -0.04839831 -0.115 -0.03958201 -0.04887968 -0.115 -0.0665968 -0.03978973 -0.115 -0.04035425 -0.06633949 -0.115 -0.05627471 -0.02801913 -0.115 -0.07115602 -0.03108406 -0.115 -0.02852743 -0.05598837 -0.115 -0.0304901 -0.07133519 -0.115 -0.01683276 -0.06056874 -0.115 -0.02065092 -0.07482731 -0.115 -0.06069606 -0.01626348 -0.115 -0.0757308 -0.01728504 -0.115 -0.006962895 -0.07736563 -0.115 -0.06281024 -0.003291726 -0.115 -0.07754653 -0.003482401 -0.115 -0.006562888 -0.06244206 -0.115 -0.07697534 0.01042705 -0.115 0.003288626 -0.06275111 -0.115 0.007574141 -0.07727891 -0.115 -0.06206357 0.009829759 -0.115 -0.07382547 0.02398729 -0.115 0.01570677 -0.06087046 -0.115 0.02065092 -0.07482731 -0.115 -0.05971306 0.0194019 -0.115 0.0304901 -0.07133519 -0.115 -0.05604112 0.02855432 -0.115 -0.06866753 0.03625148 -0.115 0.02855432 -0.05604112 -0.115 0.03984123 -0.06668287 -0.115 0.03954476 -0.04883366 -0.115 -0.04883366 0.03954476 -0.115 -0.061091 0.04793006 -0.115 0.05107218 -0.05845701 -0.115 -0.05361133 0.056073 -0.115 -0.04201203 0.04665911 -0.115 0.04665911 -0.04201203 -0.115 0.05842185 -0.0510416 -0.115 -0.04562664 0.06279969 -0.115 -0.03374803 0.05303758 -0.115 0.05303758 -0.03374803 -0.115 0.06478357 -0.04276305 -0.115 -0.03370326 0.06998586 -0.115 -0.02553737 0.0573579 -0.115 0.0714274 -0.03052949 -0.115 0.05889517 -0.02198344 -0.115 -0.01626348 0.06069606 -0.115 -0.02065092 0.07482731 -0.115 0.07567846 -0.01727312 -0.115 0.061414 -0.01305395 -0.115 0.06275111 -0.003288626 -0.115 -0.007574141 0.07727891 -0.115 -0.003871977 0.06274491 -0.115 0.07726579 -0.006954014 -0.115 0.07754653 0.003482401 -0.115 0.003480494 0.07749998 -0.115 0.009839057 0.06212204 -0.115 0.06244206 0.006562888 -0.115 0.01386052 0.07637721 -0.115 0.0757308 0.01728504 -0.115 0.06069606 0.01626348 -0.115 0.02251887 0.0586636 -0.115 0.02729427 0.07272517 -0.115 0.07137805 0.03050845 -0.115 0.05627471 0.02801913 -0.115 0.04035425 0.06633949 -0.115 0.03374803 0.05303758 -0.115 0.06514161 0.0422607 -0.115 0.05079495 0.03690469 -0.115 0.05107218 0.05845701 -0.115 0.04403769 0.04486197 -0.115 0.05842185 0.0510416 -0.115 -0.06030279 -0.04731148 -0.1 -0.05088591 -0.05731862 -0.1 -0.05429679 -0.05191308 -0.1 -0.04418522 -0.06081598 -0.1 -0.06271892 -0.04140049 -0.1 -0.0398336 -0.06548351 -0.1 -0.0677815 -0.0357837 -0.1 -0.03557592 -0.0661112 -0.1 -0.06932961 -0.02898418 -0.1 -0.02750092 -0.07154375 -0.1 -0.02639544 -0.07033061 -0.1 -0.07308167 -0.02310574 -0.1 -0.07339084 -0.01613897 -0.1 -0.01428431 -0.07530444 -0.1 -0.01670587 -0.07319325 -0.1 -0.07603293 -0.009685099 -0.1 -0.006733715 -0.07481825 -0.1 -0.07504498 -0.003370106 -0.1 -0.003435611 -0.07649999 -0.1 -0.07657706 0 -0.1 0.006738364 -0.07486999 -0.1 0.00626415 -0.07639086 -0.1 -0.07477331 0.006729722 -0.1 -0.07586956 0.01089125 -0.1 -0.07323724 0.01671588 -0.1 0.01704001 -0.07465714 -0.1 0.01998496 -0.0724135 -0.1 -0.07270556 0.02426332 -0.1 0.0263614 -0.07197141 -0.1 -0.06912326 0.02954483 -0.1 0.03261613 -0.06772822 -0.1 -0.06720471 0.03685557 -0.1 0.03878867 -0.0661078 -0.1 -0.06267684 0.04137265 -0.1 0.04135888 -0.06265604 -0.1 -0.06195217 0.04501086 -0.1 0.04774498 -0.05987036 -0.1 0.04988819 -0.05619472 -0.1 -0.05497789 0.05340629 -0.1 -0.05653727 0.04939514 -0.1 0.05497789 -0.05340629 -0.1 -0.04898959 0.05697977 -0.1 0.05912041 -0.04638379 -0.1 -0.04774498 0.05987036 -0.1 0.06195217 -0.04501086 -0.1 -0.04135888 0.06265604 -0.1 -0.03878867 0.0661078 -0.1 0.06444853 -0.0385062 -0.1 0.06720471 -0.03685557 -0.1 -0.03206527 0.06795954 -0.1 0.06932961 -0.02898418 -0.1 -0.0263614 0.07197141 -0.1 0.07270556 -0.02426332 -0.1 -0.01998496 0.0724135 -0.1 0.07339084 -0.01613897 -0.1 -0.01704001 0.07465714 -0.1 0.07586956 -0.01089125 -0.1 -0.007329881 0.07478606 -0.1 -0.00626415 0.07639086 -0.1 0.07504498 -0.003370106 -0.1 0.07657706 0 -0.1 0.003368198 0.07499998 -0.1 0.003435611 0.07649999 -0.1 0.07454204 0.009495377 -0.1 0.07603293 0.009685099 -0.1 0.01428431 0.07530444 -0.1 0.01400411 0.07382792 -0.1 0.07164871 0.02265256 -0.1 0.07308167 0.02310574 -0.1 0.02750092 0.07154375 -0.1 0.02319961 0.07140111 -0.1 0.06764078 0.03257405 -0.1 0.03314042 0.06744176 -0.1 0.0677815 0.0357837 -0.1 0.06267678 0.04137265 -0.1 0.0398336 0.06548351 -0.1 0.04135888 0.06265604 -0.1 0.04988819 0.05619472 -0.1 0.05653727 0.04939514 -0.1 0.06030279 0.04731148 -0.1 0.05088591 0.05731862 -0.1 -0.1015 -0.08406698 -0.02943295 -0.1015 -0.07342141 -0.04207855 -0.1015 -0.07642143 -0.04507851 -0.1015 -0.09056699 -0.03593295 -0.1015 -0.08406698 0.02943295 -0.1015 -0.07342141 0.04207855 -0.1015 -0.1635786 -0.04507851 -0.1015 -0.149433 -0.03593295 -0.1015 -0.07642143 0.04507851 -0.1015 -0.155933 -0.02943295 -0.1015 -0.1665786 -0.04207855 -0.1015 -0.09056699 0.03593295 -0.1015 -0.1665786 0.04207855 -0.1015 -0.155933 0.02943295 -0.1015 -0.1635786 0.04507851 -0.1015 -0.149433 0.03593295 -0.05088591 0.05731862 -0.09749996 -0.05020922 0.06319242 -0.09749996 -0.05990523 0.05393892 -0.09749996 -0.06030279 0.04731148 -0.09749996 -0.06727933 0.04458403 -0.09749996 -0.0398336 0.06548351 -0.09749996 -0.04030519 0.06981068 -0.09749996 -0.0677815 0.0357837 -0.09749996 -0.02822428 0.07561504 -0.09749996 -0.0736413 0.0327872 -0.09749996 -0.02750092 0.07154375 -0.09749996 -0.07308167 0.02310574 -0.09749996 -0.07776373 0.02161145 -0.09749996 -0.01428431 0.07530444 -0.09749996 -0.01263248 0.07975798 -0.09749996 -0.07603293 0.009685099 -0.09749996 -0.08055436 0.005283594 -0.09749996 -0.003435611 0.07649999 -0.09749996 0.004222273 0.08056563 -0.09749996 -0.07657706 0 -0.09749996 0.00626415 0.07639086 -0.09749996 -0.07586956 -0.01089125 -0.09749996 -0.07989257 -0.01157999 -0.09749996 0.01675981 0.07884889 -0.09749996 0.01704001 0.07465714 -0.09749996 -0.07270556 -0.02426332 -0.09749996 -0.0766651 -0.02490997 -0.09749996 0.02822428 0.07561504 -0.09749996 0.0263614 0.07197141 -0.09749996 -0.07240396 -0.03570139 -0.09749996 -0.06720471 -0.03685557 -0.09749996 0.03878867 0.0661078 -0.09749996 0.04030519 0.06981068 -0.09749996 -0.06339895 -0.04997485 -0.09749996 0.05020922 0.06319242 -0.09749996 -0.06195217 -0.04501086 -0.09749996 0.04774498 0.05987036 -0.09749996 -0.05497789 -0.05340629 -0.09749996 0.05497789 0.05340629 -0.09749996 -0.05162316 -0.06206417 -0.09749996 0.05990523 0.05393892 -0.09749996 -0.04774498 -0.05987036 -0.09749996 0.06727933 0.04458403 -0.09749996 0.06195217 0.04501086 -0.09749996 -0.03878867 -0.0661078 -0.09749996 0.06720471 0.03685557 -0.09749996 -0.04030519 -0.06981068 -0.09749996 -0.02962154 -0.07507872 -0.09749996 -0.0263614 -0.07197141 -0.09749996 0.0736413 0.0327872 -0.09749996 0.07270556 0.02426332 -0.09749996 0.07776373 0.02161145 -0.09749996 -0.01704001 -0.07465714 -0.09749996 -0.01675981 -0.07884889 -0.09749996 0.07586956 0.01089125 -0.09749996 -0.00626415 -0.07639086 -0.09749996 -0.00347656 -0.08063596 -0.09749996 0.08055436 0.005283594 -0.09749996 0.003435611 -0.07649999 -0.09749996 0.07657706 0 -0.09749996 0.07603293 -0.009685099 -0.09749996 0.07989257 -0.01157999 -0.09749996 0.00842607 -0.08016884 -0.09749996 0.01428431 -0.07530444 -0.09749996 0.02161145 -0.07776367 -0.09749996 0.07308167 -0.02310574 -0.09749996 0.0766651 -0.02490997 -0.09749996 0.02750092 -0.07154375 -0.09749996 0.0327872 -0.0736413 -0.09749996 0.0398336 -0.06548351 -0.09749996 0.07240396 -0.03570139 -0.09749996 0.0677815 -0.0357837 -0.09749996 0.04030519 -0.06981068 -0.09749996 0.06339895 -0.04997485 -0.09749996 0.06030279 -0.04731148 -0.09749996 0.05162316 -0.06206423 -0.09749996 0.05088591 -0.05731862 -0.09749996 -0.06709682 0.05640202 -0.1175 -0.0574972 0.06605076 -0.1175 -0.0506224 0.05887925 -0.1175 -0.05842185 0.0510416 -0.1175 -0.04638367 0.07437556 -0.1175 -0.07503855 0.04517799 -0.1175 -0.06478357 0.04276305 -0.1175 -0.03929573 0.06697195 -0.1175 -0.03478968 0.08039408 -0.1175 -0.0811975 0.03299492 -0.1175 -0.07115602 0.03108406 -0.1175 -0.02727544 0.07267487 -0.1175 -0.02396756 0.0842393 -0.1175 -0.0757308 0.01728504 -0.1175 -0.01726269 0.07563304 -0.1175 -0.01322054 0.08657902 -0.1175 -0.08594179 0.01719588 -0.1175 -0.006345987 0.07738947 -0.1175 0 0.08762937 -0.1175 -0.07754653 0.003482401 -0.1175 -0.08764171 7.87387e-4 -0.1175 0.006958067 0.07731217 -0.1175 -0.08657902 -0.01322048 -0.1175 -0.07697534 -0.01042705 -0.1175 0.01574695 0.08622765 -0.1175 -0.08430075 -0.02377432 -0.1175 0.01726269 0.07563304 -0.1175 -0.07382547 -0.02398729 -0.1175 0.02920961 0.08256816 -0.1175 0.02727544 0.07267487 -0.1175 -0.07975918 -0.03638863 -0.1175 0.03926461 0.07827466 -0.1175 -0.06989544 -0.03365987 -0.1175 0.03929573 0.06697195 -0.1175 0.04882586 0.07270997 -0.1175 -0.07257664 -0.04906666 -0.1175 -0.06514161 -0.0422607 -0.1175 0.05110752 0.05849742 -0.1175 0.05749726 0.06605076 -0.1175 -0.06508553 -0.05596292 -0.1175 -0.06650733 -0.05692154 -0.1175 -0.05842185 -0.0510416 -0.1175 -0.0506224 -0.05887925 -0.1175 0.06709682 0.05640202 -0.1175 0.06068927 0.04839831 -0.1175 -0.04983931 -0.06741321 -0.1175 -0.03929573 -0.06697195 -0.1175 0.07503861 0.04517793 -0.1175 0.06808322 0.03733736 -0.1175 0.0811975 0.03299492 -0.1175 -0.02727544 -0.07267487 -0.1175 -0.03255164 -0.07544034 -0.1175163 0.07263129 0.02725899 -0.1175 0.07567846 0.01727312 -0.1175 0.08594179 0.01719588 -0.1175 -0.01726269 -0.07563304 -0.1175 -0.01401978 -0.07970911 -0.1175 -0.006958067 -0.07731217 -0.1175 0.07760018 0.003484845 -0.1175 0.08752274 0.00323683 -0.1175 0.003480494 -0.07749998 -0.1175 0.005007803 -0.08003991 -0.1175 0.01386052 -0.07637721 -0.1175 0.07692211 -0.0104199 -0.1175 0.08726245 -0.007556796 -0.1175 0.02369529 -0.0764181 -0.1175 0.02729427 -0.07272517 -0.1175 0.07478243 -0.02063864 -0.1175 0.08434718 -0.01592254 -0.1175 0.08604991 -0.01604157 -0.1175 0.07835131 -0.03068506 -0.1175 0.07137805 -0.03050845 -0.1175 0.04122626 -0.06900018 -0.1175 0.03981369 -0.0666368 -0.1175 0.05110752 -0.05849742 -0.1175 0.06068927 -0.04839831 -0.1175 0.06987106 -0.04419296 -0.1175 0.0665968 -0.03978973 -0.1175 0.05684953 -0.05809903 -0.1175 0.320558 -0.1796412 -0.02275913 0.351 -0.1838458 -0.01711398 -0.08867383 -0.171412 -0.02231961 0.2766568 -0.1735967 -0.02080106 0.2351475 -0.1673692 -0.02179515 0.2296206 -0.1698326 -0.01366126 0.1845449 -0.1642771 -0.02244371 0.173168 -0.16685 -0.01402527 0.1297643 -0.1641794 -0.02436614 0.1326703 -0.1657959 -0.01802563 0.08383017 -0.1669912 -0.01772952 0.05848878 -0.1670139 -0.02339446 0.0236184 -0.1679427 -0.02823358 0.05673998 -0.1676543 -0.01952069 -0.04962414 -0.1709319 -0.01834022 -0.04963266 -0.1700527 -0.03793478 -0.06393575 -0.1710504 -0.02278155 -0.07581764 -0.1711754 -0.02470719 -0.08437454 -0.1712574 -0.02516055 -0.07899367 -0.1216517 -0.1388233 0.3198096 -0.1068692 -0.06243497 0.351 -0.1028692 -0.06399399 0.3192277 -0.1133988 -0.0634188 0.351 -0.1165375 -0.06594657 0.2382074 -0.1146588 -0.05181646 0.2382046 -0.1063718 -0.05033856 0.2084425 -0.1119019 -0.05020409 0.1802796 -0.1124579 -0.05261522 0.1581275 -0.1100406 -0.05634129 0.1511958 -0.1151425 -0.05906164 0.1313025 -0.1144 -0.06497865 0.1158842 -0.116051 -0.07081693 0.129149 -0.1106878 -0.06499981 0.07991254 -0.1120945 -0.08493924 0.05446183 -0.1181616 -0.09683096 0.01620715 -0.1150609 -0.112218 0.006377577 -0.1197851 -0.1164606 -0.003269076 -0.1173097 -0.1196672 -0.02651554 -0.1178614 -0.1274209 -0.03302842 -0.1208742 -0.1295331 -0.04972624 -0.1173759 -0.1333846 -0.06379085 -0.1214691 -0.1366453 -0.06954169 -0.1162302 -0.1370787 0.3193041 -0.120076 -0.06376153 0.2398217 -0.1224229 -0.0523262 0.2101652 -0.1221444 -0.05092841 0.1819437 -0.1221077 -0.05307555 0.1531953 -0.1228758 -0.05881583 0.1174921 -0.1245871 -0.07014924 0.05800223 -0.1246703 -0.09485471 0.002898693 -0.1275967 -0.1168306 -0.03576296 -0.1292542 -0.1291077 -0.06515049 -0.1301311 -0.1355616 0.351 -0.1287001 -0.06552153 0.3200045 -0.126819 -0.06343829 0.05585008 -0.1306266 -0.09455591 0.004586517 -0.1338693 -0.1145188 -0.03497987 -0.1359131 -0.1268985 -0.06477206 -0.1369869 -0.1333495 0.3207794 -0.1340995 -0.06226432 0.2340428 -0.130339 -0.05080044 0.2051573 -0.1295641 -0.0501216 0.1763275 -0.1295857 -0.05285996 0.1454241 -0.1332541 -0.05867493 0.1056578 -0.1370501 -0.07072287 0.03583663 -0.1392692 -0.09898835 -0.01008486 -0.1484122 -0.1114805 -0.04778558 -0.1510077 -0.1209959 -0.07050043 -0.1463139 -0.1286089 0.351 -0.1404261 -0.06281006 0.3193987 -0.139798 -0.06061077 0.2783455 -0.140446 -0.05409264 0.2342468 -0.1386489 -0.04845666 0.2047189 -0.1377834 -0.04774898 0.1749336 -0.1372876 -0.05064404 0.02999949 -0.1454876 -0.0977751 -0.07203978 -0.152723 -0.1243385 0.3195571 -0.1460469 -0.05820018 0.351 -0.1515023 -0.05810636 0.1399691 -0.1433429 -0.05484575 0.1011206 -0.1440256 -0.06763142 0.01283389 -0.1538636 -0.09597575 -0.02540606 -0.1575391 -0.1061275 -0.06068801 -0.1600112 -0.1128715 -0.07748973 -0.1607457 -0.1148612 0.3195952 -0.1519808 -0.05516201 0.2795009 -0.1513966 -0.04876023 0.2333778 -0.1473925 -0.04403042 0.2029024 -0.1460888 -0.04355895 0.1706713 -0.14616 -0.04623919 0.09456706 -0.1489354 -0.06554776 0.03492802 -0.1554217 -0.0833494 6.87126e-4 -0.1589674 -0.09269887 -0.04322689 -0.1626664 -0.1022799 -0.0689153 -0.1641151 -0.105988 0.3197327 -0.1575652 -0.0515201 0.351 -0.1588363 -0.05342274 0.132821 -0.1495338 -0.05121356 0.08525228 -0.1534917 -0.06276625 0.01679289 -0.1602555 -0.08034276 -0.02738118 -0.1640372 -0.08975541 -0.06116265 -0.1661226 -0.09485936 0.31999 -0.1627427 -0.04731065 0.351 -0.1675665 -0.04585921 0.2781473 -0.1608718 -0.04076039 0.2360959 -0.1544999 -0.03910982 0.198914 -0.1523373 -0.03902137 0.1627989 -0.152108 -0.04210996 0.1164101 -0.1541082 -0.04962933 0.03167814 -0.1608474 -0.06730806 -0.02569288 -0.1651365 -0.0776109 -0.06037837 -0.1669801 -0.08192503 0.3208051 -0.1695218 -0.04035025 0.2409946 -0.1607828 -0.03352695 0.2008636 -0.1579868 -0.03349554 0.1608594 -0.1557078 -0.03814905 0.1068502 -0.1578547 -0.04501831 -0.007760107 -0.1657708 -0.06177556 -0.05161941 -0.1681097 -0.06629246 0.351 -0.1734502 -0.03879266 0.2760438 -0.1681266 -0.03122597 0.1467696 -0.1607777 -0.03162187 0.08736646 -0.1614913 -0.04053831 -0.04074472 -0.16823 -0.05513256 0.3203759 -0.1752796 -0.03176784 0.351 -0.1796316 -0.02850431 0.2416754 -0.1654921 -0.02676361 0.1988278 -0.1623765 -0.02684503 0.06822508 -0.1645205 -0.03525513 0.319908 -0.1806223 0.01974642 0.351 -0.1822807 0.02212876 0.3197382 -0.1782272 0.0259754 0.2796671 -0.1739736 0.02122044 0.2276831 -0.1677507 0.01856237 0.1852987 -0.1653856 0.01886051 0.1460887 -0.1639375 0.02479922 0.1319141 -0.165313 0.02192986 0.09245443 -0.1651574 0.03325492 0.06994271 -0.1669929 0.02924388 -0.005818307 -0.1688423 0.05067276 -0.02507734 -0.1697373 0.04201078 -0.07971596 -0.170722 0.04899317 -0.0796383 -0.1707127 0.05199998 0.351 -0.1772032 0.03301638 0.3203735 -0.1752375 0.03195089 0.2360699 -0.164933 0.0259177 0.1998861 -0.1624099 0.02550798 0.163103 -0.1616235 0.0282033 0.122533 -0.162312 0.03446346 0.04859739 -0.165645 0.0504474 -0.0333141 -0.1694523 0.06699544 0.351 -0.1734377 0.03881573 0.3209797 -0.1716675 0.03748321 0.2312374 -0.1602856 0.03193926 0.1961458 -0.1593827 0.03023838 0.161119 -0.1588793 0.03343343 0.1224045 -0.1597694 0.04028135 0.05213129 -0.1633987 0.05737215 -0.03455537 -0.1663149 0.08525162 0.32018 -0.167424 0.04269975 0.351 -0.1666949 0.04669612 0.2012851 -0.1545743 0.03613638 0.1687058 -0.1540184 0.03910017 0.1337305 -0.1549835 0.04540318 0.08725094 -0.1586799 0.05531758 -0.01526516 -0.1640862 0.08639401 0.3192471 -0.1626681 0.04737913 0.2339802 -0.1545374 0.03825545 0.09174948 -0.1552624 0.05970954 0.01044553 -0.16093 0.08444911 -0.05417019 -0.1624687 0.1061642 0.351 -0.1588261 0.05343157 0.3192026 -0.1575022 0.05156528 0.2367948 -0.1503755 0.04206526 0.204679 -0.1485328 0.04134589 0.1739788 -0.148068 0.04396146 0.1417335 -0.1488251 0.05009341 0.1007757 -0.1512129 0.06176608 0.351 -0.1303295 0.06522476 0.277467 -0.1320489 0.05638188 0.2338898 -0.1279748 0.05118471 0.205514 -0.1272088 0.05046439 0.177279 -0.127231 0.05315953 0.1456502 -0.1303288 0.05950129 0.1085128 -0.1317546 0.07191431 0.03693395 -0.1355324 0.1007641 0.3202739 -0.1267186 0.06346654 0.1496615 -0.1251456 0.05942285 0.1135289 -0.1258338 0.07137024 0.04851841 -0.1276197 0.0982666 -0.001475632 -0.1289733 0.1176833 -0.03913658 -0.1297919 0.1292219 -0.05714994 -0.1300845 0.133312 0.351 -0.1200026 0.06604826 0.319256 -0.1200159 0.06376022 0.2774212 -0.1200214 0.05764991 0.2314472 -0.1199334 0.05157256 0.2036257 -0.1198973 0.05103683 0.1756221 -0.1199371 0.05399012 0.1464894 -0.1200782 0.06065517 0.1100878 -0.1203893 0.07321882 0.04148286 -0.1211659 0.102092 -0.006696999 -0.1216803 0.1206512 -0.04098457 -0.1219701 0.1309953 -0.05865037 -0.1220816 0.1349581 0.351 -0.1131011 0.065687 0.3202861 -0.1137201 0.06350976 0.2366231 -0.1120517 0.05142176 0.2064023 -0.1147734 0.05062431 0.1783674 -0.1149121 0.05322575 0.1495206 -0.115006 0.05949968 0.1136839 -0.115092 0.07154506 0.04941755 -0.115213 0.09860455 -0.001249492 -0.1152835 0.1186736 -0.03868246 -0.1153204 0.1303784 -0.05692201 -0.115333 0.1346121 0.3197863 -0.1067282 0.06240278 0.2100813 -0.1097935 0.04971975 0.1817073 -0.1100409 0.05186182 0.1529024 -0.1099573 0.05762499 0.1173192 -0.109472 0.06898027 0.05644339 -0.1081085 0.09399825 0.004075944 -0.1068859 0.114773 -0.03519505 -0.1061299 0.1272629 -0.05519169 -0.1058396 0.1320004 0.3200264 -0.0824505 0.05159729 0.351 -0.07711142 0.05029386 0.232926 -0.08993619 0.04182106 0.202534 -0.09151464 0.041341 0.1721228 -0.09190833 0.04418641 0.1356085 -0.08833891 0.04905813 0.108174 -0.08945143 0.05964446 0.01866894 -0.08348566 0.09088599 0.003641486 -0.08583116 0.1004188 -0.02655524 -0.08172869 0.1055446 -0.0337876 -0.07898873 0.1035137 -0.05453932 -0.07828468 0.108227 -0.09199744 -0.1714989 -0.009934484 -0.09273922 -0.1715452 -0.001215219 -0.09244573 -0.1713096 0.006655097 -0.09117311 -0.1710269 0.01429611 -0.08860301 -0.171007 0.0224508 -0.01177483 -0.1700286 0.01937365 0.05462205 -0.1687884 0.009098112 0.0569635 -0.1684139 0.01986354 0.05856645 -0.1682012 0.02321231 -0.04841202 -0.1707569 0.03398478 -0.06080061 -0.1707856 0.02208334 -0.07581514 -0.1709569 0.02472615 -0.08438807 -0.1710174 0.02518194 0.06168007 -0.1676781 0.02645134 0.06560802 -0.1672708 0.02851694 -0.05961334 -0.06820392 1.56966e-4 -0.08841973 -0.06799089 -5.98902e-6 0.01714128 -0.1007682 -0.1221464 0.0383538 -0.09608274 -0.1195045 -0.001369357 -0.09446829 -0.1275265 0.03787094 -0.08430385 -0.1271421 -6.74814e-5 -0.09910267 -0.1262601 -8.33345e-4 -0.08972138 -0.1278071 0.04193264 -0.1079015 -0.10482 0.05587333 -0.1096127 -0.09460896 0.01814854 -0.1039173 -0.1195792 0.03765571 -0.1013717 -0.1143046 -0.02105021 -0.08775222 -0.1283549 0.01739096 -0.10762 -0.1169969 0.03558737 -0.105822 -0.1104355 -0.02147775 -0.09301275 -0.1290295 0.01696985 -0.1115665 -0.1141466 -0.002295136 -0.1047164 -0.1248587 -0.03810161 -0.08313375 -0.1291705 -0.02138966 -0.09986728 -0.1292821 -0.002639412 -0.1083029 -0.1236552 -0.00286138 -0.1113153 -0.1226312 -0.02231097 -0.1040528 -0.1293786 -0.05494892 -0.07286763 -0.1296142 -0.07151848 -0.0607227 -0.1308221 -0.007452905 -0.1139414 -0.1236152 0.1112789 -0.03156882 -0.1230031 0.1144364 -0.01824843 -0.125953 0.1218279 -0.01863896 -0.1211393 0.1221018 -0.04233074 -0.1102229 -0.03875499 -0.09661138 -0.1317602 0.1068636 -0.01783275 -0.1300014 0.1003589 -0.01741874 -0.1318451 -0.02280211 -0.1076676 -0.1293702 0.09622943 -0.0378378 -0.1287943 0.0896961 -0.03875738 -0.1301348 -0.05939322 -0.08869373 -0.1338933 -0.04118728 -0.1015172 -0.1328703 -0.03184276 -0.1123642 -0.131763 0.122285 -0.05337446 -0.1034435 0.1000546 -0.04793113 -0.1228025 0.1131116 -0.05110603 -0.1114184 -0.04257583 -0.1076812 -0.1338889 0.08506184 -0.05288416 -0.1280578 0.1125155 -0.05708312 -0.1079208 -0.08137625 -0.06748467 -0.1343095 -0.0608046 -0.1117935 -0.1375219 -0.06271415 -0.1004106 -0.136254 0.1225022 -0.06513851 -0.09539991 -0.08168351 -0.08215653 -0.1362475 0.1175699 -0.06746405 -0.09682309 0.08806979 -0.06120461 -0.1228657 0.1079111 -0.07302856 -0.09891778 0.1004775 -0.06347262 -0.1123737 -0.09227406 -0.07490909 -0.1367263 0.06699895 -0.0652849 -0.1282587 0.1039669 -0.06865483 -0.1055259 -0.08300882 -0.0893625 -0.1371669 -0.07921767 -0.112111 -0.139098 0.09770524 -0.08048617 -0.09943807 0.09243738 -0.07012867 -0.1131324 -0.08398127 -0.09960877 -0.1382429 0.09300214 -0.07592111 -0.107401 0.08531326 -0.07494544 -0.1141268 0.084674 -0.08240634 -0.1071742 0.09028452 -0.08732372 -0.09783637 0.0735628 -0.06560087 -0.1271875 0.07223147 -0.07222908 -0.1243591 0.1142731 -0.1021773 -0.07147896 0.1231942 -0.1015568 -0.06895977 0.06601405 -0.08666533 -0.1156048 0.1232745 -0.106829 -0.065894 0.1096347 -0.1055898 -0.07079708 0.05412936 -0.07949525 -0.1264832 0.08536404 -0.09414392 -0.09366923 0.06075817 -0.08204966 -0.1226226 0.09935492 -0.1024807 -0.07734394 0.04469865 -0.08645415 -0.1251128 0.06205803 -0.0930587 -0.1107477 0.08813107 -0.1060214 -0.07980823 0.05518436 -0.09252607 -0.1154419 0.08823502 -0.1005797 -0.08495157 0.08534991 -0.09789341 -0.08953392 0.07169938 -0.1037108 -0.09150189 0.02010798 -0.0852676 -0.1273013 -0.08776783 -0.06844007 -0.02814888 -0.08825266 -0.06951433 -0.05180525 -0.09079343 -0.07237595 -0.08814519 -0.09340846 -0.0746513 -0.101975 -0.0796383 -0.06957536 0.05199998 -0.07971692 -0.06945252 0.04900008 -0.04773771 -0.06888353 0.02739936 -0.03975015 -0.07581204 0.09707963 -0.04304945 -0.07371169 0.08414524 -0.04628181 -0.07091796 0.06227463 -0.04697084 -0.06991428 0.04445213 -0.02904212 -0.1166926 -0.1292379 -0.04591476 -0.116463 -0.1335216 0.06045776 -0.1910004 -0.02032309 0.06162339 -0.1669999 -0.02652937 0.06475061 -0.1910007 -0.0246126 0.0655961 -0.1669999 -0.0285536 0.06999999 -0.1669999 -0.02925109 0.06999999 -0.191 -0.02583611 0.07440382 -0.1669999 -0.0285536 0.07524937 -0.1910007 -0.0246126 0.07837659 -0.1669999 -0.02652937 0.08211469 -0.1670003 -0.02264565 0.07963234 -0.1910004 -0.02005195 0.08513176 -0.1676921 -0.01117646 0.08223801 -0.191 -0.008560895 0.08582788 -0.1683225 -0.003333032 0.08273142 -0.191 0 0.08568263 -0.1682889 0.005717575 0.08223801 -0.191 0.008560895 0.08463943 -0.1680173 0.01382696 0.07963234 -0.1910004 0.02005195 0.08226132 -0.1673376 0.02234005 0.07840871 -0.1669802 0.02650296 0.07636928 -0.191 0.02376657 0.07440382 -0.1669999 0.0285536 0.07127559 -0.1910009 0.02589875 0.06665146 -0.191 0.02530574 0.0636307 -0.191 0.02376657 0.06036096 -0.1910004 0.01999771 0.05775994 -0.191 0.008755266 0.05419909 -0.1689759 -0.00108689 0.05726271 -0.191 -0.0024181 0.05478668 -0.1684828 -0.01006329 0.05813598 -0.191 -0.0108487 -0.05181366 -0.1909988 -0.01721578 -0.06199973 -0.191 -0.02061069 -0.07671308 -0.191 -0.02305257 -0.08325934 -0.191 -0.02340126 -0.08752632 -0.1910003 -0.02053207 -0.09065788 -0.191 -0.007452189 -0.09101837 -0.191 0.002002358 -0.0899598 -0.191 0.01176249 -0.08734732 -0.191 0.02074897 -0.08325934 -0.191 0.02340126 -0.07671302 -0.191 0.02305251 -0.06546628 -0.191 0.02133238 -0.05194365 -0.1910123 0.01732003 -0.04625308 -0.1893155 0.0151295 0.3202196 -0.1830782 -0.009822785 0.351 -0.1860799 -0.002515017 0.2798618 -0.1766331 -0.01183336 0.2757871 -0.1773035 -0.002560913 0.2365171 -0.172106 -0.0030393 0.1886788 -0.1685135 -0.006136655 0.1404033 -0.1679124 -0.003106832 0.1328664 -0.166979 -0.01166629 0.3201667 -0.1837566 8.13317e-5 0.184884 -0.168659 0.002592265 0.320092 -0.1834 0.006734728 0.351 -0.1852215 0.01033544 0.2776448 -0.1769489 0.00905174 0.2317767 -0.1710863 0.007728815 0.1398312 -0.1676556 0.007019579 0.3199858 -0.1823509 0.01331722 0.1840559 -0.1675318 0.01073211 0.1387857 -0.16693 0.01344066 0.3199885 -0.05660641 0.006691157 0.351 -0.0539543 2.46294e-6 0.3202915 -0.05625057 -0.003335058 0.2750709 -0.06278258 0.001590132 0.2272472 -0.06875723 -0.00219196 0.2288919 -0.06937915 0.008679747 0.1944001 -0.07125902 0.005284965 0.1844019 -0.07140362 -0.002931594 0.1371573 -0.07229459 0.006787955 0.134997 -0.07210177 -2.16316e-6 0.056629 -0.07073634 0 0.05668205 -0.07082945 0.004040896 0.04421561 -0.07068198 0.01173758 0.04407793 -0.07051718 0.003594934 0.320012 -0.05764341 0.01328617 0.351 -0.05477827 0.01033431 0.2791526 -0.06347525 0.01206111 0.1804029 -0.07259356 0.01101726 0.1201266 -0.07288801 0.01459383 0.04391717 -0.07118654 0.02168953 0.3191941 -0.07733362 0.04738092 0.2772902 -0.08142775 0.0428313 0.2297198 -0.08359354 0.0361638 0.1984443 -0.08537024 0.03611862 0.165833 -0.0860024 0.03955525 0.08429622 -0.08413523 0.06228411 0.0285654 -0.08032059 0.08023995 0.3194392 -0.07261776 0.04266351 0.351 -0.07091039 0.04418766 0.2754566 -0.07530671 0.03605091 0.127556 -0.08345085 0.04435372 0.08296716 -0.08115154 0.05564999 0.03375476 -0.07797461 0.06849932 0.3196056 -0.06842261 0.03748226 0.351 -0.0639351 0.03496605 0.2343013 -0.07654964 0.02826011 0.1987364 -0.08047997 0.03028398 0.162748 -0.08112323 0.03323596 0.1227163 -0.08034521 0.03981626 0.08178961 -0.07855123 0.04886245 0.03679519 -0.07621049 0.05940574 0.3208798 -0.0647155 0.03189033 0.2013125 -0.07748889 0.02580857 0.1620581 -0.07837295 0.02835768 0.1356742 -0.07810908 0.03159391 0.1066422 -0.07726281 0.03623914 0.03981226 -0.07435333 0.04852128 0.351 -0.0596593 0.02685183 0.3197289 -0.06033623 0.02261549 0.278744 -0.06633722 0.0215432 0.2297194 -0.07226383 0.01931166 0.1863175 -0.0747838 0.01962393 0.1397896 -0.07521188 0.02293205 0.09483009 -0.07497918 0.03073185 0.04246485 -0.07253003 0.03412103 0.351 -0.05718648 0.02040928 0.09322679 -0.07352459 0.0242986 0.3186256 -0.09690707 -0.05946493 0.351 -0.09001231 -0.05883681 0.2378686 -0.09897577 -0.04754549 0.2084832 -0.1019398 -0.04725432 0.1803145 -0.1024688 -0.04954522 0.1580699 -0.1028622 -0.05391961 0.1334365 -0.1006684 -0.05970656 0.1333709 -0.1081088 -0.06286001 0.351 -0.05447965 -0.008693754 0.2785553 -0.06292325 -0.009036779 0.1346806 -0.07283192 -0.01220667 0.3200183 -0.05764293 -0.01328349 0.227737 -0.0704891 -0.01335823 0.1851705 -0.07284289 -0.01306879 0.351 -0.05771625 -0.02212131 0.3198904 -0.05937957 -0.01975339 0.2788758 -0.06507545 -0.01792758 0.1652027 -0.0748381 -0.01946455 0.1343262 -0.07571148 -0.02573925 0.3197522 -0.06177824 -0.02598839 0.2749716 -0.06910353 -0.02637726 0.2309514 -0.07298094 -0.02082538 0.1947879 -0.07618421 -0.02282762 0.351 -0.06367439 -0.03458601 0.31955 -0.06481796 -0.03194218 0.229927 -0.07725799 -0.02833694 0.1666916 -0.07833713 -0.02775055 0.1340374 -0.07993382 -0.03677159 0.3210456 -0.06837934 -0.03759551 0.1986209 -0.08164101 -0.03152197 0.1691007 -0.08252084 -0.03461492 0.351 -0.07209259 -0.04553961 0.3198098 -0.07256591 -0.04268294 0.2314728 -0.08184754 -0.0342009 0.1338491 -0.08385127 -0.04395157 0.3189583 -0.0773831 -0.04742789 0.2360777 -0.08532691 -0.03833967 0.2041185 -0.087179 -0.03746694 0.1740815 -0.08784413 -0.04006952 0.154769 -0.08778977 -0.04353153 0.133724 -0.08737874 -0.04872709 0.351 -0.0811854 -0.05344122 0.318883 -0.08258163 -0.05162888 0.2366926 -0.09191173 -0.04358375 0.2074069 -0.09320414 -0.04239189 0.1787237 -0.09377717 -0.04465252 0.1569892 -0.09399431 -0.04882335 0.13357 -0.09310692 -0.0546019 0.3189423 -0.08818471 -0.05525815 -0.03635454 -0.1707133 -0.01188594 -0.02773177 -0.1706532 -0.00594449 -0.02571696 -0.1707139 -7.7045e-4 -0.02642244 -0.170611 0.003542184 -0.02828454 -0.170537 0.0064103 -0.03476417 -0.1704907 0.01087713 -0.04538708 -0.1706207 0.0165863 0.06578636 -0.05779099 -0.01261091 0.05862027 -0.05863863 -0.0116235 0.05796271 -0.06560391 -0.00295031 0.0483787 -0.06761306 -5.05507e-4 0.06000643 -0.06794619 -2.56188e-5 -0.05145275 0.06234884 -0.09266245 -0.0627377 0.06204521 -0.09256231 -0.06135076 0.05254971 -0.08946633 -0.07130396 0.05211752 -0.08933871 -0.04141891 0.06920099 -0.0947383 -0.04529011 0.07562059 -0.0960139 -0.05551564 0.06851208 -0.09461987 -0.02963656 0.07511758 -0.09591227 -0.01390081 0.07954961 -0.09671217 0.08509671 -0.02058631 -0.04699695 0.07986015 -0.01795965 -0.04912418 0.07629072 -0.03060227 -0.0387755 0.08201575 -0.03074401 -0.03863942 0.1342515 -0.04252064 -0.02858352 0.1267669 -0.02057898 -0.04699999 0.1272578 -0.04278731 -0.02824962 0.1337066 -0.01759028 -0.04939925 0.1279107 -0.06530511 -0.00331813 0.1346585 -0.05740827 -0.01304155 0.1276561 -0.05740827 -0.01304155 0.135 -0.06799995 0 0.1253361 -0.06799995 0 -0.07048308 -0.05634313 -0.01423704 -0.06549328 -0.05638855 -0.1222537 -0.0678423 -0.05813646 -0.1274297 0.09531694 -0.01706504 -0.1318044 0.09017246 -0.01664382 -0.1294607 0.08653044 -0.01629054 -0.1257002 0.0845533 -0.01602065 -0.1206735 0.08810049 -0.01445132 -0.05163836 0.1232979 -0.01726812 -0.06499999 0.1312979 -0.01782751 -0.06499999 0.1333503 -0.01791852 -0.06300067 0.06112265 -0.06898945 0 0.1229969 -0.0702905 0 0.1233062 -0.1044054 -0.06502437 0.0808987 -0.02878403 -0.124096 -0.01984941 -0.08354061 -0.1266573 -0.03666675 -0.07948076 -0.1274982 0.05039119 -0.06683772 -0.1249073 0.03588724 -0.07466638 -0.1244613 0.07985806 -0.02848857 -0.121062 -0.03568685 -0.07710474 -0.1251491 0.03506749 -0.07327795 -0.1222609 0.05187565 -0.06847524 -0.1265766 0.03688603 -0.0761407 -0.1259533 0.08399087 -0.02978479 -0.1280519 -0.05065053 -0.06743758 -0.1214981 0.05370509 -0.07054352 -0.1275631 0.03828072 -0.08036291 -0.1275066 0.08698982 -0.03044658 -0.1298311 -0.03479981 -0.07545781 -0.1220099 0.01805448 -0.07892554 -0.1220578 0.08619523 -0.03761994 -0.1300386 0.07380676 -0.04056572 -0.1230662 0.01844108 -0.08031332 -0.1241971 -0.05225449 -0.06948024 -0.1263094 0.01896989 -0.08182942 -0.1256895 0.07627928 -0.04147815 -0.1265742 -8.52307e-4 -0.0812782 -0.121999 0.07850271 -0.04262799 -0.1284357 -8.74381e-4 -0.08265697 -0.1241453 -8.80946e-4 -0.08527797 -0.1265008 0.06262063 -0.05447065 -0.1230162 0.06430363 -0.05564177 -0.1256129 -0.01878041 -0.07977908 -0.121778 0.06605374 -0.05689209 -0.1272376 0.06873667 -0.05883622 -0.1283873 -0.01928377 -0.08122336 -0.1243103 0.04915487 -0.06550723 -0.1225662 0.1224426 -0.06918746 -0.09766548 0.1223965 -0.07618695 -0.09942156 0.1230755 -0.1024605 -0.07349139 0.122887 -0.1019676 -0.08069056 0.1224034 -0.082183 -0.09916126 0.1224386 -0.08734297 -0.09781396 0.1227033 -0.09917497 -0.08770847 0.1225448 -0.09411358 -0.0937618 0.08900493 -0.003807902 -0.05934953 0.08134949 -0.007238268 -0.05692201 -0.05857586 -0.05868279 -0.01160782 -0.04717981 -0.06844133 5.82921e-4 0.07371926 -0.04735058 -0.02374035 0.0688728 -0.04549908 -0.0256139 -0.06886494 -0.04551136 -0.02560412 -0.07801705 -0.04470062 -0.02636027 -0.07427591 -0.05108171 -0.01970821 0.07781475 -0.04019415 -0.0303412 -0.07628619 -0.03061366 -0.03877729 -0.08264267 -0.03505331 -0.03493684 -0.07989346 -0.0178132 -0.04921966 -0.08584105 -0.02545559 -0.04297679 -0.08134722 -0.007265806 -0.05690991 -0.08900493 -0.003807902 -0.05934947 -0.08793699 -0.01573932 -0.05073636 -0.07963287 0.01619231 -0.07188409 -0.08856463 0.007876634 -0.06669479 -0.08151602 0.003516435 -0.06394767 0.08856463 0.007876634 -0.06669479 0.07963287 0.01619231 -0.07188409 0.08151602 0.003516435 -0.06394767 -0.07718461 0.02507877 -0.07666903 -0.07411581 0.03278201 -0.08080619 -0.08645659 0.02030819 -0.07413113 0.07718461 0.02507877 -0.07666903 0.07411581 0.03278201 -0.08080619 0.08645659 0.02030819 -0.07413113 -0.06835699 0.04349714 -0.08562314 -0.07634258 0.04457932 -0.08611011 -0.08186793 0.03370547 -0.08124101 0.06135076 0.05254971 -0.08946633 0.06835699 0.04349714 -0.08562314 0.07634258 0.04457926 -0.08611011 0.08186793 0.03370547 -0.08124101 0.05551564 0.06851208 -0.09461987 0.04141891 0.06920099 -0.0947383 0.05145275 0.06234884 -0.09266245 0.0627377 0.06204521 -0.09256231 0.07130396 0.05211752 -0.08933871 0.04259663 0.0772261 -0.09638679 0.03030967 0.08274465 -0.09694766 0.01969861 0.08588492 -0.09718674 0.00877881 0.087673 -0.09732288 -0.002768039 0.08808332 -0.09735405 -0.01426666 0.08695024 -0.0972678 -0.0250535 0.08448117 -0.09707987 -0.03685891 0.0800417 -0.09681415 0 0.08062916 -0.09678661 0.01390081 0.07954961 -0.09671217 0.02963656 0.07511758 -0.09591227 0.06235337 -0.0677843 -0.04699999 0.06803101 -0.05525821 -0.04699999 0.05916607 -0.06452226 -0.04700005 0.08256816 -0.02920961 -0.04699999 0.1217662 -0.06903362 -0.04699999 0.07735604 -0.04123467 -0.04699999 0.1267669 -0.06413698 -0.04699999 -0.0267198 -0.1800466 -0.002210378 -0.02921372 -0.1815211 -0.005977511 -0.03702765 -0.1856483 -0.01070845 -0.04609805 -0.1892572 -0.01506763 -0.03738254 -0.1858385 0.01089888 -0.02919697 -0.181504 0.00596255 -0.02692234 -0.1801651 0.002668917 0.351 -0.1022698 0.04675078 0.351 -0.07145291 0.01196575 0.351 -0.07572716 0.02323615 0.351 -0.09159672 0.04114913 0.351 -0.08257442 0.03315609 0.351 -0.1574255 -0.03315609 0.351 -0.1484032 -0.04114913 0.351 -0.1642728 -0.02323615 0.351 -0.1377302 -0.04675078 0.351 -0.168547 -0.01196575 0.351 -0.1260268 -0.04963541 0.351 -0.17 0 0.351 -0.1139732 -0.04963541 0.351 -0.168547 0.01196575 0.351 -0.1022698 -0.04675078 0.351 -0.1642728 0.02323615 0.351 -0.09159672 -0.04114913 0.351 -0.1574255 0.03315609 0.351 -0.08257442 -0.03315609 0.351 -0.1484032 0.04114913 0.351 -0.07572716 -0.02323615 0.351 -0.1377302 0.04675078 0.351 -0.07145291 -0.01196575 0.351 -0.1260268 0.04963541 0.351 -0.06999999 0 0.351 -0.1139732 0.04963541 -0.08466553 -0.191 0.01688635 -0.07989066 -0.191 -0.009968698 -0.08276152 -0.191 -0.01072287 -0.07501858 -0.191 -0.01571494 -0.07620471 -0.191 0.01163768 -0.07938343 -0.191 0.009922623 -0.07756507 -0.191 -0.01059579 -0.08276152 -0.191 0.01927703 -0.08301985 -0.191 -0.01909875 -0.0849784 -0.191 -0.01606541 -0.07542121 -0.191 -0.0127741 -0.07938343 -0.191 -0.02007734 -0.08466553 -0.191 -0.01311361 -0.08301985 -0.191 0.01090121 -0.07989066 -0.191 0.02003121 -0.0849784 -0.191 0.01393455 -0.07620471 -0.191 -0.01836228 -0.07756507 -0.191 0.01940417 -0.07542121 -0.191 0.0172258 -0.07501858 -0.191 0.01428502 0.07076919 -0.191 -0.009967267 0.07379525 -0.191 -0.01836228 0.07177299 -0.191 0.01032489 0.06592142 -0.191 0.01794797 0.06499052 -0.191 0.01560819 0.07498139 -0.191 -0.01571494 0.06551033 -0.191 -0.01735633 0.06775861 -0.191 0.01950573 0.06756508 -0.191 -0.01940417 0.07379525 -0.191 0.01163768 0.07474309 -0.191 -0.01331806 0.07061648 -0.191 -0.02007734 0.06499052 -0.191 -0.01439172 0.07341814 -0.191 -0.01130652 0.0701093 -0.191 0.02003121 0.06576639 -0.191 0.01207774 0.06592142 -0.191 -0.01205193 0.07508867 -0.191 0.01484304 0.06923079 -0.191 0.009967267 0.06775861 -0.191 -0.01049417 0.0724349 -0.191 0.01940417 0.07420271 -0.191 0.01776808 0.341 -0.09159672 -0.04114913 0.341 -0.08257442 -0.03315609 0.341 -0.1022698 -0.04675078 0.341 -0.07572716 -0.02323615 0.341 -0.07145291 -0.01196575 0.341 -0.06999999 0 0.341 -0.07145291 0.01196575 0.341 -0.1139732 -0.04963541 0.341 -0.1377302 -0.04675078 0.341 -0.1260268 -0.04963541 0.341 -0.07572716 0.02323615 0.341 -0.08257442 0.03315609 0.341 -0.09159672 0.04114913 0.341 -0.1574255 -0.03315609 0.341 -0.1484032 -0.04114913 0.341 -0.1642728 -0.02323615 0.341 -0.168547 -0.01196575 0.341 -0.1022698 0.04675078 0.341 -0.1139732 0.04963541 0.341 -0.1260268 0.04963541 0.341 -0.17 0 0.341 -0.168547 0.01196575 0.341 -0.1642728 0.02323615 0.341 -0.1377302 0.04675078 0.341 -0.1484032 0.04114913 0.341 -0.1574255 0.03315609 0.06304186 -0.04069596 -0.05549997 0.0630567 0.0407058 -0.05549997 0.06308597 -0.04075109 -0.03899997 0.06311351 0.04073727 -0.03899997 -0.04070127 -0.06303656 -0.05549997 0.04070502 -0.06302785 -0.05549997 -0.04071635 -0.06304514 -0.03899997 0.04070591 -0.06304854 -0.03899997 -0.06305062 -0.04072737 -0.03899997 -0.06300169 0.04069435 -0.03899997 -0.0630567 0.0407058 -0.05549997 -0.06304186 -0.04069596 -0.05549997 -0.05356782 0.021209 -0.03899997 -0.05665934 0.01080828 -0.03899997 -0.05764538 -0.003626704 -0.03899997 -0.05468982 -0.01844602 -0.03899997 -0.02123379 -0.05363047 -0.03899997 -0.01079571 -0.05659317 -0.03899997 -6.43153e-4 -0.05771321 -0.03899997 0.01079571 -0.05659317 -0.03899997 0.02123379 -0.05363047 -0.03899997 0.05485796 -0.01782435 -0.03899997 0.05755895 -0.004265725 -0.03899997 0.05715936 0.007220864 -0.03899997 0.05485796 0.01782435 -0.03899997 0.0178036 0.05479383 -0.03899997 0.007229328 0.05722624 -0.03899997 -0.007239162 0.0573039 -0.03899997 -0.02184367 0.05342364 -0.03899997 -0.06907546 0.02952438 -0.05549997 -0.07237005 0.01997286 -0.05549997 -0.07444077 0.01008379 -0.05549997 -0.07507556 0 -0.05549997 -0.07449227 -0.01009076 -0.05549997 -0.07128 -0.02378749 -0.05549997 -0.06764078 -0.03257405 -0.05549997 -0.03206533 -0.06795954 -0.05549997 0.0325936 -0.06768137 -0.05549997 -0.01998496 -0.0724135 -0.05549997 -0.006738364 -0.07486999 -0.05549997 0.006733715 -0.07481825 -0.05549997 0.01999872 -0.07246357 -0.05549997 0.06932961 0.02898418 -0.05549997 0.07339084 0.01613897 -0.05549997 0.07504498 0.003370106 -0.05549997 0.07454204 -0.009495377 -0.05549997 0.06764078 -0.03257405 -0.05549997 0.07164871 -0.02265256 -0.05549997 0.006733715 0.07481825 -0.03899997 0.01941549 0.07259285 -0.03899997 -0.05912041 0.04638379 -0.03899997 0.03206527 0.06795954 -0.03899997 -0.0518819 0.05426424 -0.03899997 0.04368454 0.06114196 -0.03899997 -0.0441547 0.06077396 -0.03899997 -0.03314042 0.06744176 -0.03899997 -0.05653727 -0.04939514 -0.03899997 0.05389988 0.0523591 -0.03899997 -0.04988819 -0.05619472 -0.03899997 -0.01400411 0.07382792 -0.03899997 -0.02319961 0.07140111 -0.03899997 0.04680883 -0.05869644 -0.03899997 0.05429679 -0.05191308 -0.03899997 -0.003368198 0.07499998 -0.03899997 -0.04675078 -0.01773023 -0.135 -0.03315609 -0.03742551 -0.135 -0.04114913 -0.02840322 -0.135 -0.04963541 0.006026804 -0.135 -0.04963541 -0.006026804 -0.135 0.01196575 -0.04854708 -0.135 0 -0.04999995 -0.135 -0.01196575 -0.04854708 -0.135 -0.04675078 0.01773023 -0.135 0.03315609 -0.03742551 -0.135 0.02323615 -0.04427278 -0.135 -0.02323615 -0.04427278 -0.135 -0.01196575 0.04854708 -0.135 -0.03315609 0.03742551 -0.135 -0.02323615 0.04427278 -0.135 -0.04114913 0.02840322 -0.135 0.04963541 -0.006026804 -0.135 0.04114913 -0.02840322 -0.135 0.04675078 -0.01773023 -0.135 0.04963541 0.006026804 -0.135 0.01196575 0.04854708 -0.135 0 0.04999995 -0.135 0.03315609 0.03742551 -0.135 0.04675078 0.01773023 -0.135 0.04114913 0.02840322 -0.135 0.02323615 0.04427278 -0.135 -0.04675078 0.01773023 -0.125 -0.04114913 0.02840322 -0.125 -0.03315609 0.03742551 -0.125 0 0.04999995 -0.125 0.01196575 0.04854708 -0.125 -0.02323615 0.04427278 -0.125 0.02323615 0.04427278 -0.125 -0.01196575 0.04854708 -0.125 0.03315609 0.03742551 -0.125 0.04114913 0.02840322 -0.125 0.04675078 0.01773023 -0.125 0.04963541 0.006026804 -0.125 0.04963541 -0.006026804 -0.125 0.04675078 -0.01773023 -0.125 0.04114913 -0.02840322 -0.125 0.03315609 -0.03742551 -0.125 0.02323615 -0.04427278 -0.125 0.01196575 -0.04854708 -0.125 0 -0.04999995 -0.125 -0.01196575 -0.04854708 -0.125 -0.02323615 -0.04427278 -0.125 -0.03315609 -0.03742551 -0.125 -0.04114913 -0.02840322 -0.125 -0.04675078 -0.01773023 -0.125 -0.04963541 -0.006026804 -0.125 -0.04963541 0.006026804 -0.125 0.009829759 0.06206357 -0.125 -0.002707839 0.06280595 -0.125 0.06280595 0.002707839 -0.125 -0.05598837 0.02852743 -0.125 0.01683276 -0.06056874 -0.125 0.02852743 -0.05598837 -0.125 0.061414 0.01305395 -0.125 0.03690469 -0.05079495 -0.125 -0.05079495 0.03690469 -0.125 -0.04486197 0.04403769 -0.125 0.0194019 0.05971306 -0.125 0.04403769 -0.04486197 -0.125 0.0586636 0.02251887 -0.125 0.02801913 0.05627471 -0.125 0.05303758 0.03374803 -0.125 0.03690469 0.05079495 -0.125 -0.03425586 -0.05274933 -0.125 -0.04443264 -0.04443264 -0.125 -0.03690469 0.05079495 -0.125 -0.05240267 -0.03472572 -0.125 0.05079495 -0.03690469 -0.125 0.04486197 0.04403769 -0.125 -0.02852743 0.05598837 -0.125 0.05627471 -0.02801913 -0.125 -0.02251887 -0.0586636 -0.125 -0.0573579 -0.02553737 -0.125 -0.06075322 -0.0162788 -0.125 0.06069606 -0.01626348 -0.125 -0.003288626 -0.06275111 -0.125 -0.01305395 -0.061414 -0.125 -0.0162788 0.06075322 -0.125 -0.06275111 -0.003288626 -0.125 0.006562888 -0.06244206 -0.125 0.06244206 -0.006562888 -0.125 -0.06244206 0.006562888 -0.125 -0.06056874 0.01683276 -0.125 -0.07804876 -0.1809999 0.01029759 -0.07579725 -0.1809999 0.01223188 -0.08109796 -0.1809999 0.01008874 -0.08325451 -0.1809999 0.0111615 -0.08471834 -0.1809999 0.01321053 -0.07723844 -0.1809999 0.01927703 -0.07499223 -0.1809999 0.01450198 -0.08480989 -0.1809999 0.01682412 -0.07533442 -0.1809999 0.01688629 -0.08010929 -0.1809999 0.02003121 -0.08243495 -0.1809999 0.01940417 -0.07499223 -0.1809999 -0.01549792 -0.07533442 -0.1809999 -0.01311367 -0.0757972 -0.1809999 -0.01776808 -0.07723844 -0.1809999 -0.01072287 -0.07804876 -0.1809999 -0.01970231 -0.08010929 -0.1809999 -0.009968698 -0.08471834 -0.1809999 -0.01678943 -0.08492302 -0.1809999 -0.01378655 -0.0810979 -0.1809999 -0.01991122 -0.08301985 -0.1809999 -0.01090121 -0.08325451 -0.1809999 -0.0188384 0.07195121 -0.1809999 0.01029759 0.07420271 -0.1809999 0.01223182 0.06890201 -0.1809999 0.01008874 0.06674546 -0.1809999 0.01116156 0.06528162 -0.1809999 0.01321053 0.07370483 -0.1809999 0.01849186 0.07045757 -0.1809999 0.02007049 0.07508867 -0.1809999 0.01515692 0.06519007 -0.1809999 0.01682412 0.06756508 -0.1809999 0.01940417 0.07508867 -0.1809999 -0.01484304 0.07420271 -0.1809999 -0.01776808 0.07370483 -0.1809999 -0.0115081 0.07195121 -0.1809999 -0.01970231 0.07045757 -0.1809999 -0.009929478 0.06528162 -0.1809999 -0.01678943 0.06507688 -0.1809999 -0.01378655 0.06890201 -0.1809999 -0.01991117 0.06698012 -0.1809999 -0.01090121 0.06674546 -0.1809999 -0.0188384 -0.074 -0.09056699 0.05646699 -0.074 -0.149433 0.05646699 -0.074 -0.08406698 0.062967 -0.074 -0.155933 0.062967 -0.1005 -0.08406698 -0.02943295 -0.1005 -0.08406698 0.02943295 -0.1005 -0.09056699 -0.03593295 -0.1005 -0.149433 -0.03593295 -0.1005 -0.155933 -0.02943295 -0.1005 -0.155933 0.02943295 -0.1005 -0.149433 0.03593295 -0.1005 -0.09056699 0.03593295 -0.09299999 -0.155933 -0.062967 -0.09299999 -0.155933 -0.121833 -0.09299999 -0.149433 -0.128333 -0.09299999 -0.09056699 -0.128333 -0.09299999 -0.08406698 -0.121833 -0.09299999 -0.08406698 -0.062967 -0.09299999 -0.09056699 -0.05646699 -0.09299999 -0.149433 -0.05646699 + + + + + + + + + + 0 0 1 0 0 1 -1.54461e-7 0 1 2.9568e-7 0 1 -9.85253e-7 0 1 5.67022e-7 0 1 -3.95505e-7 0 1 2.32094e-7 0 1 -7.57975e-7 0 1 1.2238e-6 0 1 -1.79955e-7 0 1 -3.71302e-7 0 1 1.02876e-6 0 1 -0.8577511 0.5138361 0.01534891 -0.8555217 0.5169171 0.02965426 -0.7369519 -0.6757434 -0.01651871 -0.6022965 -0.7982702 -0.00189048 -0.6715518 -0.7408717 -0.01128411 -0.6096549 -0.7926072 0.009739995 0.6004801 -0.7996381 -0.001652598 0.6119223 -0.7907698 0.01531475 0.6793507 -0.7337093 -0.01238703 0.6878432 -0.7257965 -0.009553611 0.7065334 0.7076618 -0.00504291 0.5855873 0.8102803 -0.02310061 0.5797478 0.814573 -0.01906532 0.6119225 0.7907696 0.01531475 -0.6004801 0.7996381 -0.001652598 -0.6119223 0.7907698 0.01531475 -0.7213937 0.6922783 -0.01849412 -1 -4.34943e-5 -6.05662e-5 -1 8.44351e-7 0 -1 0 -2.11821e-7 -0.9999999 -5.85059e-4 2.11724e-4 -0.9999573 0.003874957 -0.008405804 -1 -1.05125e-5 -6.76137e-5 -1 -8.41074e-6 3.87682e-6 -1 -5.75085e-6 2.76965e-5 -1 0 -8.59748e-6 -1 2.60362e-6 0 -1 0 2.16419e-7 -1 -9.65319e-7 0 -1 -3.51617e-5 -7.5796e-5 -1 1.33999e-6 0 -1 0 0 -1 -1.40284e-6 0 -1 0 3.79203e-6 -1 -7.10196e-7 3.63237e-7 -1 5.83339e-6 1.37622e-6 -1 2.74613e-5 1.36286e-5 -1 3.5066e-6 -2.9379e-6 -1 -8.56685e-6 0 -1 4.15738e-6 -7.54493e-6 -1 -2.99214e-5 -1.16506e-6 -1 7.01419e-7 0 -1 1.17331e-5 5.10332e-6 -1 -1.41467e-5 -1.22228e-5 -1 7.7592e-6 7.94539e-6 -1 1.51889e-5 5.69117e-6 -1 0 -3.42703e-5 -1 -9.38184e-6 -1.78972e-5 -1 8.77134e-6 -8.08373e-6 -1 -4.40101e-7 -2.3645e-5 -1 -4.632e-5 0 -1 1.38083e-4 1.18472e-5 -1 0 0 -1 -9.49137e-6 -7.52074e-7 -1 4.58426e-6 1.3972e-6 -1 -3.49999e-5 -3.90631e-6 -1 -2.03028e-6 0 -1 -5.54225e-7 0 -0.999997 0.001067042 -0.002267301 -1 7.32782e-5 2.56184e-5 -1 3.63056e-4 -9.39429e-5 -1 2.01184e-6 -1.73479e-6 -1 1.05765e-6 -1.4666e-6 -1 1.77703e-6 1.75996e-6 -1 -2.49775e-4 -8.7612e-5 -1 -2.57205e-5 1.20849e-5 -1 -1.15414e-4 -1.99562e-5 -1 0 -8.34054e-6 -1 -6.96402e-6 -7.24255e-6 -1 -1.41888e-6 -3.46933e-5 -1 -6.50886e-6 -8.39715e-6 -1 -2.32345e-6 -2.58737e-6 -0.06696009 -0.4530642 0.8889597 -0.1496171 -0.4348196 0.8880016 -0.1309988 -0.4184576 0.8987394 -0.1337259 -0.4307737 0.8924974 -0.02594995 -0.4292774 0.9027999 -0.03383862 -0.4503786 0.8921962 0.08792555 -0.4526813 0.8873268 0.08355319 -0.4638726 0.881953 0.1920371 -0.4953815 0.847183 0.1927017 -0.4937663 0.8479746 0.2697338 -0.5852693 0.7646592 0.2834891 -0.5426618 0.7906656 0.3129266 -0.6202107 0.7193161 0.2632831 -0.7565816 0.5985536 0.2497798 -0.7489456 0.6137512 0.2075912 -0.7951596 0.5697606 0.1912674 -0.7860657 0.5878074 0.1609527 -0.805912 0.5697369 0.2839021 -0.2802967 0.9169697 0.1307395 -0.7827687 0.6084246 0.1103042 -0.8068115 0.5804208 -0.07653367 -0.357331 0.9308368 -0.07690834 -0.3584399 0.9303795 -0.1377556 -0.3530554 0.9254055 0.2886735 -0.4400691 0.8502981 0.3446924 -0.4717188 0.8115841 0.3278574 -0.5391001 0.7758098 0.2906475 -0.5525231 0.7811801 0.3105317 -0.5143491 0.7993842 0.2306906 -0.5681534 0.7899263 0.2483994 -0.5428912 0.8022263 0.1661567 -0.5638858 0.8089653 0.154563 -0.5920377 0.79095 0.1004251 -0.5585508 0.8233686 0.1632974 -0.5469493 0.8210849 -0.06570017 0.332091 0.9409565 -0.07151889 0.3581804 0.9309092 -0.1408792 0.342993 0.9287136 -0.1392909 0.3686732 0.9190637 -0.03623974 0.3790761 0.9246557 -0.03662812 0.3809172 0.9238834 0.08268398 0.4057884 0.9102194 0.08605951 0.3962748 0.9140899 0.1952298 0.4228618 0.8849143 0.1940344 0.4261019 0.8836221 0.2985243 0.4473618 0.8430603 0.3410703 0.4833419 0.8062579 0.3229296 0.4604316 0.8268733 0.3063893 0.5129438 0.8018818 0.2546437 0.4971934 0.8294308 0.2450854 0.5218332 0.8170822 0.1667007 0.5175242 0.8392733 0.16681 0.5193669 0.8381125 0.1115042 0.5332031 0.8386068 0.1645491 0.5291765 0.8324037 -0.07142066 0.4528409 0.8887262 -0.07144957 0.452959 0.8886637 -0.1417437 0.4493295 0.8820498 -0.1414438 0.4458375 0.8838679 -0.03177922 0.4470515 0.8939436 0.269658 0.5476661 0.792052 0.3304289 0.5613003 0.7587878 0.2938733 0.6771689 0.6745968 0.2775481 0.6669737 0.6914573 0.2515583 0.7220351 0.6445028 0.2111937 0.7248023 0.6557888 0.2008931 0.7417373 0.6398968 0.1408654 0.7357003 0.6624969 0.1322189 0.7517216 0.6460905 0.1742546 -0.3982924 0.9005546 -1.18903e-6 0 -1 2.26578e-6 0 -1 1.51555e-6 0 -1 0 0 -1 5.15774e-7 0 -1 -7.22232e-7 0 -1 1.2354e-6 0 -1 3.78891e-7 0 -1 -2.84129e-7 0 -1 -1.14275e-6 0 -1 2.21393e-7 0 -1 -8.33991e-7 0 -1 1.23538e-6 0 -1 -2.99065e-7 0 -1 3.76529e-7 0 -1 -7.16268e-7 0 -1 1.58669e-6 0 -1 1.50405e-6 0 -1 -1.15e-6 0 -1 -1.68716e-6 0 -1 -1.55069e-7 0 -1 -3.81661e-7 0 -1 -2.86896e-7 0 -1 1.57713e-6 0 -1 -1.19609e-6 0 -1 -7.87531e-7 0 -1 6.2409e-7 0 -1 -1.19619e-6 0 -1 5.89744e-7 0 -1 7.45218e-7 0 -1 -7.18753e-7 0 -1 -7.65476e-7 0 -1 2.39615e-6 0 1 -3.62519e-6 0 1 -3.39579e-6 -1.89148e-6 1 -3.3591e-6 0 1 0 -8.20531e-6 1 -1.54841e-6 -5.23895e-6 1 -1.95073e-6 5.52055e-7 1 8.50068e-7 -3.28629e-6 1 -1.00964e-5 0 1 0 3.93354e-6 1 8.95195e-6 -5.65994e-7 1 0 4.46388e-6 1 0 -2.40333e-7 1 1.42062e-5 -8.19986e-7 1 -1.56435e-5 9.02943e-7 1 0 1.13107e-6 1 0 2.26961e-7 1 1.29429e-6 4.38911e-6 1 6.94176e-6 0 1 0 3.65321e-6 1 7.25034e-6 0 1 -3.39572e-6 -2.68293e-6 1 0 -2.55572e-6 1 0 -3.19685e-6 1 0 2.71842e-6 1 -3.91088e-6 2.71065e-6 1 0 -2.44163e-6 1 0 2.97843e-6 1 0 2.4185e-6 1 -2.4061e-6 0 1 -4.5255e-6 -3.46883e-6 1 0 2.17372e-6 1 0 -3.17359e-6 1 0 3.19685e-6 1 0 1.2406e-6 1 0 -1.34705e-6 1 0 2.71536e-6 1 -3.20042e-6 -8.70482e-7 1 3.54678e-6 0 1 4.81213e-6 0 1 2.23796e-6 -3.65319e-6 1 -3.05213e-6 -5.36033e-6 1 -5.06823e-6 0 1 1.62799e-5 -4.29533e-7 1 -2.14749e-7 4.687e-7 1 -2.00131e-6 0 1 -5.43843e-6 -1.75065e-7 1 0 7.63821e-7 1 2.2246e-6 0 1 1.81527e-6 -1.30208e-7 1 1.54809e-7 8.55831e-6 1 7.26091e-6 -6.65892e-7 1 0 2.27762e-6 1 0 2.10095e-6 1 -6.77981e-6 2.21496e-6 1 3.54675e-6 0 1 0 3.12894e-6 1 8.16347e-6 5.25317e-6 1 0 1.01559e-6 1 0 6.60387e-6 1 -1 -1.53793e-6 0 -1 7.68963e-7 0 -1 7.68963e-7 0 0 2.65137e-6 1 -2.57829e-6 1.31204e-7 1 -2.53199e-6 -1.52853e-7 1 -3.92011e-6 2.77289e-6 1 -3.87881e-6 1.85654e-6 1 -2.11612e-6 1.27747e-7 1 0 1.74415e-6 1 0 3.36612e-6 1 0 -1.80641e-7 1 -9.96556e-7 0 1 -9.29918e-7 3.71176e-6 1 -2.05936e-6 3.48387e-6 1 -3.48693e-6 7.52699e-7 1 -3.78327e-6 6.75694e-7 1 -2.33426e-7 4.02877e-6 1 0 3.48854e-6 1 -4.21841e-6 1.95882e-7 1 1.44538e-6 3.5891e-6 1 -6.81799e-6 -1.44383e-7 1 -2.94135e-6 -2.66388e-7 1 -1.19191e-6 3.20252e-6 1 -1.8198e-6 -8.4228e-7 1 -4.24348e-6 1.07534e-6 1 1.23451e-6 0 1 1.12032e-6 3.56452e-6 1 -1.91959e-6 -1.29718e-6 1 0 -1.38646e-6 1 1.03564e-6 3.29479e-6 1 0 4.22099e-7 1 -2.28023e-6 -2.10262e-6 1 2.49228e-6 -4.83784e-7 1 0 -2.06663e-6 1 0 2.95766e-6 1 -3.73392e-6 -2.22218e-6 1 4.37029e-6 2.69737e-6 1 -2.84417e-6 -2.858e-6 1 0 1.4465e-6 1 -2.84381e-6 -2.63283e-6 1 2.78857e-6 2.48936e-6 1 5.81822e-7 -1.46781e-6 1 -1.32779e-6 -3.04437e-6 1 1.5893e-6 1.8996e-6 1 0 4.21151e-7 1 -2.01648e-6 -3.20761e-6 1 1.22415e-6 -4.75248e-7 1 2.32603e-6 1.91638e-6 1 5.1063e-6 -3.05811e-7 1 0 -3.68234e-6 1 -8.25917e-7 0 1 3.92981e-6 7.95765e-7 1 1.13228e-6 -3.04231e-6 1 7.65338e-6 6.83448e-7 1 3.11526e-7 -3.53631e-6 1 4.94796e-6 2.2406e-7 1 3.26597e-6 -2.27483e-7 1 7.01912e-6 -1.48643e-7 1 -2.53072e-6 -1.61657e-6 1 6.35888e-7 0 1 1.16301e-6 -1.74419e-6 1 4.05692e-6 -7.6627e-7 1 0 9.96399e-7 1 0 -3.2792e-6 1 0 -1.74142e-6 1 4.0028e-6 -1.3578e-6 1 -1.2556e-6 -1.15183e-6 1 4.18682e-6 -2.00396e-6 1 3.26229e-6 -2.05688e-6 1 1.99106e-6 -2.81676e-6 1 1.10602e-6 1.33537e-7 1 2.07645e-6 -2.50286e-6 1 2.69499e-6 -2.70811e-6 1 0 3.78921e-7 -1 1.06026e-6 -5.29241e-7 -1 0 -3.74063e-7 -1 -1.7339e-6 -5.68998e-7 -1 2.19823e-6 -4.47504e-7 -1 0 -5.97586e-7 -1 0 -2.61274e-7 -1 1.73619e-6 2.15705e-7 -1 1.72266e-6 0 -1 8.58268e-7 0 -1 0 -2.19687e-7 -1 1.58061e-6 -2.3139e-7 -1 -1.80893e-6 -3.97937e-7 -1 1.44556e-6 0 -1 1.6539e-6 0 -1 -1.70293e-6 -7.24991e-7 -1 0 -5.204e-7 -1 1.64012e-6 0 -1 1.52465e-6 -7.68275e-7 -1 -2.18357e-6 -7.20031e-7 -1 0 0 -1 0 -7.34281e-7 -1 -7.76567e-7 5.94999e-7 -1 -1.08011e-6 0 -1 2.19379e-6 2.75892e-7 -1 8.13267e-7 -3.86985e-7 -1 0 3.62123e-7 -1 1.07744e-6 0 -1 -1.37067e-5 -1.64285e-5 -1 0 3.5485e-7 -1 -1.64661e-6 -5.0488e-7 -1 0 -7.89112e-7 -1 -4.31468e-7 0 -1 0 3.89557e-7 -1 0.00146681 0.003094017 -0.9999942 -7.82301e-5 0.001862883 -0.9999983 -2.07106e-6 -3.01422e-7 -1 -2.26007e-6 -2.20376e-7 -1 0 -2.18487e-7 -1 1.86446e-6 0 -1 0.001554369 0.002929151 -0.9999945 -7.9612e-7 0 -1 -1.261e-6 0 -1 0 -5.35263e-7 -1 2.21944e-6 0 -1 -4.49948e-7 0 -1 -1.5962e-6 0 -1 -1.32821e-6 0 -1 2.06185e-6 0 -1 2.14794e-6 0 -1 -1.54888e-6 0 -1 -3.19287e-6 0 -1 -0.06505221 -0.9358816 -0.3462572 -0.002280414 -0.9995957 -0.02834355 -0.1294196 -0.9211978 -0.3669402 -0.0536096 -0.9450048 -0.3226326 -0.0471788 -0.9356618 -0.3497301 0.008190214 -0.9593392 -0.2821373 -8.59443e-4 -0.9690959 -0.2466828 0.02209568 -0.9662957 -0.2564848 0.03701448 -0.9861555 -0.1616401 0.04612797 -0.9886989 -0.1426423 0.03842282 -0.9955721 -0.08579009 0.03469443 -0.998393 -0.04480808 0.02980887 -0.9963208 -0.08035236 0.02217715 -0.9987489 -0.04482179 0.01836073 -0.9986587 -0.04841434 0.01618903 -0.9984793 -0.05269974 0.01157259 -0.9992164 -0.03785294 0.01127904 -0.9992401 -0.03731364 -0.06465435 0.141121 -0.9878789 -0.06909602 0.1546517 -0.9855499 -0.1423688 0.1598652 -0.9768185 -0.1433635 0.1737098 -0.9743058 -0.03704279 0.1754368 -0.9837936 0.1871968 0.2519258 -0.9494687 0.2871459 0.1168063 -0.9507385 0.3303927 0.1863979 -0.9252548 0.2674344 0.4723537 -0.8398576 0.3720494 0.08257943 -0.9245322 0.3769148 0.1940719 -0.9056884 0.3795988 0.1845272 -0.906562 0.3417679 0.1253278 -0.9313902 0.3761084 0.04841458 -0.92531 0.3163208 0.003805935 -0.9486446 0.3152239 -0.01620072 -0.9488791 0.2492438 0.1336563 -0.9591734 0.2252123 0.00229305 -0.9743071 0.1888662 0.1267692 -0.973786 0.140586 0.07264411 -0.9873998 0.09211128 0.1558895 -0.9834704 0.07120269 0.1162799 -0.990661 -0.07427293 0.05027472 -0.99597 -0.1422066 0.03537541 -0.9892047 -0.1436545 0.049093 -0.9884095 -0.04822385 0.06238454 -0.9968866 -0.04648458 0.05581396 -0.9973586 0.08392381 0.06191736 -0.9945467 0.07570785 0.08300089 -0.9936696 0.2141918 0.02434372 -0.9764882 0.1931262 0.07995641 -0.9779108 0.3161634 -0.0146414 -0.9485918 0.3001561 0.04732608 -0.9527155 0.3910648 -0.06601923 -0.9179923 0.3835301 1.00804e-5 -0.9235284 0.3785991 -0.1251705 -0.9170579 0.3728803 -0.07791817 -0.9246022 0.3158014 -0.09592896 -0.9439635 0.3050868 -0.1473154 -0.9408614 0.2258053 -0.1227419 -0.966409 0.2163221 -0.1545613 -0.9640102 0.1420247 -0.144802 -0.9792147 0.07246887 -0.1544302 -0.9853424 0.1031699 -0.2058903 -0.9731214 -0.06485962 -0.03485321 -0.9972856 -0.07028293 -0.05504864 -0.9960071 -0.1403396 -0.06195127 -0.9881634 0.3773499 -0.181892 -0.9080322 0.3726134 -0.1802948 -0.9103039 0.3656275 -0.2336699 -0.9009522 0.3020044 -0.268004 -0.9148592 0.3006266 -0.257556 -0.9183075 0.2135563 -0.2892922 -0.9331151 0.2126519 -0.2850685 -0.9346204 0.1018545 -0.3053079 -0.9467908 0.1005741 -0.300482 -0.9484701 -0.07618671 -0.1666276 -0.9830721 -0.1444869 -0.1724892 -0.9743568 -0.1343943 -0.09205722 -0.9866427 -0.04796451 -0.1551697 -0.9867228 -0.02583247 -0.09081834 -0.9955324 0.07471174 -0.1575018 -0.9846885 0.09416538 -0.09927934 -0.9905941 0.1972719 -0.1759623 -0.9644278 0.2011633 -0.1637431 -0.9657751 0.3041372 -0.2402519 -0.9218349 0.3024601 -0.2447998 -0.92119 0.375845 -0.3167998 -0.8708493 0.3562443 -0.3893042 -0.8494306 0.3557016 -0.3875107 -0.8504775 0.3183404 -0.4906145 -0.8111454 0.2862676 -0.4639388 -0.8383386 0.2421193 -0.5245733 -0.8162114 0.2004854 -0.49962 -0.842725 0.1699812 -0.5274744 -0.8323925 0.09903156 -0.4985372 -0.8611931 -0.06462335 -0.224816 -0.972256 -0.07218456 -0.2617813 -0.962424 -0.1484068 -0.2422574 -0.9587944 -0.1377593 -0.295962 -0.9452137 -0.1328914 -0.2720685 -0.9530575 -0.02990108 -0.2720131 -0.9618289 -0.03110474 -0.27567 -0.960749 0.09096586 -0.2806615 -0.9554865 0.08779698 -0.2900651 -0.9529712 0.2109724 -0.3053412 -0.9285781 0.3424137 -0.4791161 -0.8082082 0.3171721 -0.459587 -0.8295672 0.1515204 -0.5730337 -0.8054029 0.07105332 -0.5507727 -0.8316255 0.07648772 -0.5655232 -0.821178 -0.06493419 -0.3900567 -0.9184984 -0.07188808 -0.3605568 -0.9299629 -0.1407936 -0.3594239 -0.9224921 0.1811074 -0.4330582 -0.8829841 0.2963904 -0.4747862 -0.8286923 0.273017 -0.5326282 -0.8011049 0.3342573 -0.5550106 -0.7617318 0.2839454 -0.7183473 -0.6351001 0.2751191 -0.7043896 -0.6543277 0.235215 -0.7543346 -0.6129058 0.2130461 -0.7351199 -0.6435915 0.1692946 -0.7828667 -0.5987146 0.1405538 -0.7666952 -0.6264369 0.1062388 -0.7882212 -0.6061525 0.06522488 -0.7798083 -0.6226113 0.05365538 -0.7891348 -0.6118722 -0.07626259 -0.4548109 -0.8873169 -0.1485492 -0.4455695 -0.8828369 -0.1470935 -0.451538 -0.8800437 -0.1313441 -0.4451781 -0.8857569 -0.1292396 -0.4376091 -0.8898289 -0.03455215 -0.4486469 -0.8930409 -0.03286123 -0.4444409 -0.8952054 0.07813578 -0.4626147 -0.8831095 0.07410192 -0.4717918 -0.8785905 0.1889657 -0.5080001 -0.8403736 0.2499753 -0.6414594 -0.7252878 0.2789481 -0.6659528 -0.6918779 0.2686135 -0.779268 -0.566205 0.2213878 -0.8423542 -0.4913522 0.2145968 -0.8355014 -0.5058515 0.1665174 -0.8928099 -0.4185243 0.1501967 -0.8718465 -0.466181 0.09003782 -0.8990856 -0.4284138 0.1100763 -0.9060448 -0.408615 0.04449558 -0.90973 -0.4128093 0.05227482 -0.9157797 -0.3982648 -0.07297015 -0.5367938 -0.840552 -0.0699445 -0.546125 -0.8347786 -0.1400855 -0.5432874 -0.827777 0.1561751 -0.6277388 -0.7625964 0.2459331 -0.6858232 -0.6849551 0.2076271 -0.7826868 -0.5867645 0.2444531 -0.8178152 -0.5209808 0.1833951 -0.9136763 -0.3627146 0.1886865 -0.9205934 -0.3419141 0.1415939 -0.9484803 -0.2834367 0.1416558 -0.9485907 -0.283036 0.08867877 -0.9676187 -0.2363266 0.09384715 -0.9698573 -0.2248768 0.04106223 -0.9764606 -0.2117518 0.04302966 -0.9775394 -0.2063134 -0.06633359 -0.6533588 -0.7541367 -0.07264876 -0.631337 -0.7720984 -0.1484507 -0.6254988 -0.7659724 -0.1476653 -0.6283212 -0.7638111 -0.1329663 -0.598033 -0.7903648 -0.1254819 -0.6294887 -0.7668105 -0.03735011 -0.5784361 -0.8148722 -0.03524309 -0.5724135 -0.8192074 0.06676542 -0.6138451 -0.7865981 0.06266695 -0.6237945 -0.7790722 0.1543186 -0.6930837 -0.7041454 0.1396563 -0.7319785 -0.6668611 0.1898187 -0.8507305 -0.4901292 0.1582442 -0.8948772 -0.4173172 0.1507606 -0.9646913 -0.2159675 0.1068857 -0.9887792 -0.1043617 0.1023818 -0.98155 -0.1614855 0.07204407 -0.994919 -0.07032811 0.06508266 -0.9929641 -0.09892743 0.03250408 -0.9971503 -0.06807947 -0.07947432 -0.7187492 -0.6907123 -0.1389333 -0.717516 -0.6825455 -0.1352611 -0.7149778 -0.6859382 -0.04275107 -0.7060995 -0.706821 -0.04824036 -0.6842193 -0.7276791 0.05148094 -0.7514699 -0.657756 0.04462331 -0.6906265 -0.7218337 0.1350179 -0.7652673 -0.6293935 0.09757989 -0.8617397 -0.4978786 0.1564704 -0.8999893 -0.4068616 0.09529775 -0.9771081 -0.1902056 0.1011168 -0.9829018 -0.1538817 0.06625014 -0.9918546 -0.1087916 0.0644868 -0.991529 -0.1127465 0.03572857 -0.9965398 -0.07504737 0.03011339 -0.9955931 -0.08881282 -0.0668264 -0.7667737 -0.6384296 -0.1502878 -0.7705188 -0.6194469 -0.1221687 -0.776681 -0.6179332 0.02166008 -0.8116773 -0.5837044 0.09512817 -0.8751451 -0.4744171 0.07338923 -0.9062098 -0.4164106 0.1088925 -0.9487836 -0.2965674 0.0602768 -0.9957707 -0.06933671 0.06025379 -0.9957642 -0.06945037 0.0278998 -0.9987331 -0.04187816 0.02879887 -0.9988307 -0.03883022 -0.06678313 -0.8552746 -0.5138534 -0.07868021 -0.8260314 -0.5581054 -0.1389715 -0.8191438 -0.5564983 -0.1351325 -0.8194561 -0.556984 -0.05771422 -0.8220027 -0.5665515 -0.05890262 -0.8247573 -0.5624109 0.02432823 -0.8377488 -0.5455136 0.05997842 -0.9441425 -0.3240334 0.08030241 -0.9620794 -0.2606813 0.05641633 -0.990626 -0.1244084 0.0399217 -0.9955904 -0.08488899 0.0274288 -0.995443 -0.09132897 -0.08143228 -0.8977137 -0.4329887 -0.1474196 -0.879362 -0.4527581 -0.1419569 -0.8920673 -0.4290271 -0.1266474 -0.881411 -0.4550552 -0.1185471 -0.867323 -0.4834226 -0.0648052 -0.9023677 -0.4260668 -0.04560089 -0.8547235 -0.5170768 0.006355941 -0.925384 -0.3789776 0.01241886 -0.9162356 -0.4004473 0.05943608 -0.9501301 -0.306138 0.04222524 -0.9772108 -0.2080292 0.01533716 -0.998219 -0.05765253 -0.07694935 -0.9313085 0.3560104 -0.1400117 -0.9254536 0.3520405 0.01908081 -0.9350526 0.3539953 0.05405521 -0.9779406 0.2017682 0.04793334 -0.9824056 0.1805042 0.03289568 -0.999006 0.03008079 0.05890083 -0.9906896 0.1227394 0.005832672 -0.9999786 0.00297141 0.01630103 -0.9997767 -0.01344925 -0.06536698 -0.9043564 0.4217427 -0.07278782 -0.8888227 0.4524335 -0.1472191 -0.8782152 0.4550435 -0.1397281 -0.8944832 0.424707 -0.1284419 -0.8683158 0.4790934 -0.06778872 -0.9034113 0.4233824 -0.04516804 -0.8710845 0.4890519 0.009054601 -0.919946 0.3919408 0.03369688 -0.8967973 0.4411566 0.06507736 -0.9459473 0.3177242 0.07499027 -0.9372741 0.340432 0.0849564 -0.9782992 0.188979 0.05872195 -0.9908284 0.1216998 0.05879861 -0.9963545 0.06181019 0.03597033 -0.9990823 0.02325463 0.02277183 -0.9995619 0.01890808 0.02807295 -0.9995973 0.004170775 -0.07258522 -0.8364934 0.5431485 -0.07344722 -0.8342908 0.5464106 -0.1400223 -0.8249071 0.5476515 -0.1387876 -0.8347421 0.5328636 -0.06329751 -0.8139866 0.5774248 -0.04688125 -0.8577868 0.5118633 0.0225861 -0.833876 0.5514897 0.03053772 -0.8802756 0.4734789 0.09022879 -0.8674013 0.4893607 0.09179687 -0.9116995 0.4004716 0.09963935 -0.9602776 0.2606511 0.1438001 -0.90562 0.3989662 0.08079898 -0.9813986 0.1741505 0.1138483 -0.9606096 0.2535107 -0.06618112 -0.7581566 0.6487054 -0.07357317 -0.7791317 0.6225278 -0.1365866 -0.7786221 0.6124474 -0.0512098 -0.7517269 0.6574833 0.04480385 -0.7871015 0.6151942 0.0419014 -0.7919538 0.6091417 0.1215144 -0.827929 0.5475106 0.113503 -0.8386732 0.5326765 0.1660783 -0.8765295 0.45179 0.14499 -0.9030143 0.4044049 0.144441 -0.938641 0.3131935 0.1000003 -0.9727501 0.2091825 0.04374426 -0.9871472 0.1537107 0.05603867 -0.9833608 0.172804 -0.07450127 -0.7067871 0.7034924 -0.1415399 -0.7082539 0.6916234 -0.1408414 -0.7009983 0.6991174 -0.04342615 -0.7294257 0.6826803 0.1722996 -0.855138 0.4889293 0.1382362 -0.946579 0.2913401 0.2014831 -0.8622928 0.464603 0.09510987 -0.9593661 0.2656518 0.06991589 -0.9673787 0.243496 -0.06598168 -0.6488577 0.7580437 -0.07162529 -0.6283476 0.7746284 -0.1417281 -0.6239739 0.7684853 -0.1425933 -0.6141116 0.7762308 -0.0491845 -0.6362509 0.7699128 -0.05442392 -0.6539353 0.7545906 0.05675709 -0.661337 0.7479385 0.05303066 -0.6690361 0.7413356 0.1436736 -0.7109791 0.6883798 0.1490097 -0.7014492 0.6969686 0.2198864 -0.755636 0.6169799 0.2096228 -0.7719918 0.6000726 0.1764836 -0.9116504 0.3711431 0.2396147 -0.8076861 0.5387281 0.1393867 -0.9356063 0.3243644 0.1630026 -0.9118888 0.3766817 0.115492 -0.9454452 0.3046227 0.06149107 -0.9646589 0.2562267 -0.0717141 -0.5432536 0.8365004 -0.0762487 -0.5250601 0.8476426 -0.1421678 -0.5269429 0.8379257 -0.1413632 -0.5224754 0.8408544 -0.1325857 -0.5858146 0.7995263 -0.04842883 -0.5083877 0.8597655 -0.03203356 -0.5868895 0.8090332 0.06381231 -0.532996 0.8437081 0.07645493 -0.6117907 0.7873163 0.1667892 -0.5662912 0.8071528 0.1745839 -0.6446143 0.744307 0.2501634 -0.6081443 0.7533783 0.2493671 -0.6922845 0.6771693 0.2765228 -0.6806397 0.6784282 0.1404245 -0.8364594 0.5297325 0.1015661 -0.8433169 0.5277319 0.09856313 -0.8383462 0.536154 -0.06361877 -0.2320263 0.9706268 -0.1489088 -0.2741859 0.9500781 -0.1320778 -0.2806013 0.9506937 -0.1376857 -0.2501516 0.9583669 -0.02752691 -0.2627856 0.9644616 -0.03134042 -0.2512921 0.9674038 0.09233498 -0.269111 0.9586729 0.09177255 -0.267322 0.9592272 0.2057398 -0.2882303 0.9351976 0.2164854 -0.3275703 0.9196912 0.3065281 -0.3304255 0.89267 0.3082325 -0.3591111 0.8809267 0.358628 -0.35003 0.8653699 0.3552372 -0.4424632 0.8234276 0.3274326 -0.4462957 0.8328313 -0.07671046 -0.1747842 0.9816141 -0.1402936 -0.1698096 0.9754396 -0.1348231 -0.2055861 0.9693076 0.2082459 -0.1465348 0.9670373 0.3179419 -0.1838994 0.9301043 0.3097108 -0.2257134 0.9236519 0.376951 -0.2370835 0.8953768 0.3724849 -0.2645725 0.889526 0.3371541 -0.3145569 0.887345 0.3572285 -0.2379173 0.9032073 0.2714293 -0.3152515 0.9093639 0.2870918 -0.2752031 0.9175193 0.215512 -0.3062195 0.9272455 0.1784399 -0.3569304 0.9169297 0.1547251 -0.3173898 0.9355875 -0.06623613 -0.07931071 0.994647 -0.07175987 -0.05453246 0.9959301 -0.1442093 -0.06516116 0.9873995 -0.1401323 -0.03730934 0.9894296 -0.130715 -0.087336 0.9875657 -0.02685469 -0.05629354 0.9980531 -0.01929336 -0.08298856 0.9963638 0.09492897 -0.05330818 0.9940557 0.1045879 -0.08903044 0.9905226 0.216307 -0.06181192 0.9743669 0.2224208 -0.09669315 0.9701441 0.314339 -0.03393924 0.948704 0.3250168 -0.1133542 0.9388903 0.3829976 -0.07064867 0.9210438 0.3862204 -0.1209805 0.9144384 0.3614216 -0.1513357 0.9200391 0.3579597 -0.1205289 0.9259253 0.291935 -0.1737393 0.9405258 0.2868343 -0.1468638 0.9466558 0.2209219 -0.1657131 0.9611102 0.2170987 -0.1574522 0.9633675 0.1588228 -0.1702582 0.9725161 0.1570228 -0.1665377 0.9734522 -0.07181328 0.05213141 0.9960548 -0.07164835 0.05135476 0.9961071 -0.1442474 0.06289339 0.987541 -0.13014 0.1043263 0.9859917 -0.1419472 0.04607808 0.9888013 -0.01905572 0.09048426 0.9957156 -0.02984082 0.03870469 0.9988051 0.104287 0.09362715 0.9901305 0.09220612 0.03015726 0.9952832 0.2217326 0.08870989 0.971064 0.2123066 0.03256154 0.9766606 0.324684 0.07742518 0.9426482 0.3184449 0.02556759 0.9475966 0.3875787 0.02326697 0.9215431 0.3878639 0.02779048 0.9212976 0.3595677 -0.0177809 0.9329497 0.3676613 0.05383312 0.9284003 0.288897 -0.01120585 0.9572947 0.2981504 0.04091852 0.9536415 0.2189125 -0.00603795 0.9757258 0.2260822 0.01209414 0.9740332 0.1585016 -3.44921e-4 0.9873587 0.1622678 0.009031653 0.9867055 -0.06589305 0.1827859 0.9809421 -0.07292735 0.1508682 0.9858602 -0.1386476 0.145184 0.979642 -0.04472053 0.210434 0.9765847 0.08927297 0.2113238 0.9733307 0.07360041 0.1253439 0.9893797 0.2068434 0.2157981 0.9542784 0.1946837 0.1384134 0.971051 0.3102285 0.2212705 0.9245527 0.3025296 0.1470405 0.9417299 0.3791111 0.2094734 0.9013301 0.377799 0.170912 0.9099764 0.3609772 0.194705 0.9120228 0.3637576 0.2261472 0.9036249 0.2918601 0.2058821 0.9340398 0.2984276 0.2398447 0.923805 0.2203583 0.2211894 0.9500092 0.2273408 0.2341614 0.9452432 0.1579673 0.228941 0.9605376 0.1608535 0.2344363 0.9587314 -0.07478517 0.2623037 0.9620832 -0.1428877 0.2653309 0.9535108 -0.138024 0.2232615 0.9649372 -0.04046136 0.2529781 0.9666256 -0.03281962 0.2205656 0.9748198 0.06865441 0.316847 0.9459887 0.08955794 0.2328813 0.9683727 0.1861549 0.3294097 0.9256542 0.2056239 0.2560346 0.9445449 0.2890144 0.3509933 0.8906595 0.2998694 0.3096958 0.902312 0.3600084 0.3716018 0.8557488 0.3623723 0.3636774 0.8581522 0.3535742 0.3405186 0.8712247 0.328534 0.4151213 0.8483749 0.2889677 0.3608317 0.8867346 0.2629019 0.4186325 0.8692695 0.2172734 0.3942834 0.892935 0.1527495 0.4122958 0.8981537 0.1720001 0.446671 0.8780097 -0.06425976 0.572364 0.8174779 -0.07139408 0.5453754 0.8351458 -0.1415488 0.5494794 0.8234297 -0.1393367 0.5235162 0.8405452 -0.04554247 0.5458081 0.8366717 -0.04104471 0.5333286 0.8449119 0.07635092 0.5439878 0.8356122 0.07001686 0.5596514 0.825765 0.1826167 0.5772657 0.7958741 0.1629859 0.6219245 0.7659279 0.2451062 0.6653786 0.70512 0.2479804 0.7077766 0.6614817 0.292748 0.6814627 0.6707513 0.2499054 0.7856615 0.5659357 0.2426332 0.7815117 0.5747771 0.2634624 0.6615807 0.7020674 0.1633325 0.8283348 0.5358955 0.1805704 0.805919 0.5638164 0.1476027 0.8384437 0.5246195 0.1167671 0.825273 0.5525305 0.1020788 0.8386169 0.5350718 0.0164687 -0.9998611 -0.002594292 0.02057617 -0.999782 -0.003561913 6.38688e-4 -0.9999977 -0.002105057 0.06774753 -0.9973279 0.02734088 0.002734899 -0.9988611 0.047634 -0.02064907 -0.9989706 0.04039239 0.0206502 -0.9997785 -0.004075765 0.01685208 -0.9998557 -0.00216329 0.02326089 -0.9992883 0.02969688 0.02307724 -0.9983605 0.05238258 0.02523481 -0.9995911 0.01345252 0.01472496 -0.9998082 -0.01291579 0.009999215 -0.9999182 -0.007991731 0.003856837 -0.9999451 -0.009757637 0.00676459 -0.9999623 -0.005451679 0.008028745 -0.9999656 -0.002156972 0.02833563 -0.9986085 0.0444777 0.04459226 -0.9920899 0.1173425 0.04374033 -0.9926848 0.1125333 0.0249328 -0.9982122 0.05432242 0.006773173 -0.9997183 0.02275067 1.49172e-4 -0.9999966 0.002632558 0.04422342 -0.9922855 0.1158184 0.01851415 0.9996863 0.01687002 0.01151937 0.9997352 0.01992082 0.007308244 0.999861 0.0149948 -0.03318732 0.9994222 0.007344007 0.07263749 -0.243857 -0.9670872 0.02580994 -0.06190967 -0.9977481 0.3707963 -0.6898071 -0.621833 0.2245448 -0.5715806 -0.7892245 0.2710947 -0.6927815 -0.6682525 0.2818168 -0.5869781 -0.7589703 0.3020589 -0.7015419 -0.6454451 0.0695669 -0.0667088 -0.9953444 0.03893977 0.1239776 -0.9915207 0.3657837 -0.5096465 -0.7787573 0.3401868 -0.6892935 -0.6396464 0.3270578 -0.5759814 -0.7491854 0.2261222 -0.5710365 -0.7891681 0.1927271 -0.3089746 -0.9313383 0.07993596 0.1203861 -0.9895037 0.07719743 0.0377044 -0.9963027 0.1446262 -0.2228111 -0.9640739 0.2481312 -0.329506 -0.9109647 0.2732765 -0.5872567 -0.7618723 0.1444562 -0.2932454 -0.9450606 0.3081586 -0.3264616 -0.8935666 0.3149148 -0.5775607 -0.7531616 0.2193831 -0.02578413 -0.9752981 0.3694036 -0.3188289 -0.8728626 0.3536003 -0.5099695 -0.7841543 0.5095282 -0.2994223 -0.8066768 0.5543809 -0.342988 -0.7583015 0.1482084 0.03831911 -0.9882135 0.1164218 0.1819632 -0.9763889 0.2478477 -0.3295087 -0.911041 0.2191439 -0.03205299 -0.9751659 0.4383669 -0.2921451 -0.8499916 0.2227343 -0.1879653 -0.9565869 0.2561444 -0.1933071 -0.9471127 0.1572238 0.2163765 -0.9635674 0.1653885 0.1389534 -0.9763906 0.1796786 -0.01685291 -0.983581 0.2715996 -0.03276365 -0.9618526 0.2947562 -0.3269487 -0.8978995 0.3016175 -0.1762851 -0.9369902 0.4812463 -0.3053954 -0.8216664 0.422182 -0.3001016 -0.8553956 0.1783789 -0.02653473 -0.9836041 0.4989343 -0.406909 -0.765173 0.1685281 0.178108 -0.969472 0.2213445 0.1102384 -0.9689449 0.5507546 -0.3868791 -0.7395905 0.2222163 0.06778383 -0.9726383 0.2251173 -0.2136215 -0.9506251 0.5451033 -0.463257 -0.6987528 0.209114 0.1898841 -0.9592786 0.5071641 -0.4447628 -0.7382212 0.210678 0.199581 -0.9569652 0.1950629 0.0018453 -0.9807891 0.1608036 0.1413235 -0.9768162 0.1589574 0.1515125 -0.9755904 0.5116712 -0.4713762 -0.7183293 0.1408708 0.126738 -0.9818823 0.4490477 -0.4986482 -0.7414218 0.510424 -0.499661 -0.6998617 0.160346 0.1256462 -0.9790313 0.4310061 -0.3603948 -0.8272541 0.3957267 -0.3532628 -0.8477063 0.461117 -0.5334948 -0.7090518 0.5142903 -0.4681748 -0.7185527 0.1314336 0.1271023 -0.9831431 0.1405711 -0.1890086 -0.9718619 0.5284137 -0.5279709 -0.6648503 0.163966 0.1363354 -0.9769995 0.1310948 0.1599714 -0.9783779 0.1337919 0.1011783 -0.985831 0.5264998 -0.527024 -0.667116 0.08250004 0.1239888 -0.9888482 0.4626621 -0.5867973 -0.6645396 0.4696525 -0.4830819 -0.7389577 0.5407539 -0.4849764 -0.6873015 0.1075569 0.1063428 -0.9884952 0.09905838 0.07922065 -0.9919232 0.09624052 0.0949164 -0.9908223 0.4858054 -0.5598611 -0.6712294 0.07547348 0.07480382 -0.9943381 0.4997117 -0.590531 -0.6336888 0.530662 -0.5694463 -0.6277969 0.4631515 -0.5399086 -0.7028439 0.06178188 0.09843838 -0.9932236 0.09650599 0.1044712 -0.9898346 0.4998695 -0.6129995 -0.6118515 0.04760855 0.06219536 -0.9969279 0.0271092 0.07848751 -0.9965465 0.452818 -0.6044151 -0.655468 0.4489871 -0.6346297 -0.6290118 0.3697478 -0.3919904 -0.8423956 0.1483944 -0.2004585 -0.9683985 0.4447903 -0.5424709 -0.7126619 0.4734743 -0.629563 -0.6160134 0.3745201 -0.42653 -0.8232902 0.4339448 -0.6338336 -0.6402711 0.2690768 -0.4810824 -0.8343605 0.2507636 -0.505776 -0.8254141 0.4144509 -0.5957145 -0.6880078 0.07357788 -0.1889858 -0.9792194 0.06951844 -0.09903174 -0.992653 0.4200742 -0.6742089 -0.6074373 0.4043996 -0.5952419 -0.6943688 0.3099502 -0.5729058 -0.7587555 0.1502431 -0.3830915 -0.9114099 0.3054755 -0.621488 -0.7214135 0.3374738 -0.5268433 -0.7800948 0.286185 -0.6406356 -0.7125197 0.3673754 -0.6960089 -0.6169335 0.3404669 -0.6480734 -0.6812366 0.3833484 -0.6873192 -0.6169574 0.4051604 -0.6986702 -0.5896652 0.3524838 -0.6463645 -0.6767334 0.4229279 -0.6898257 -0.587599 0.3044131 -0.6879333 -0.6588479 0.3815185 -0.6854317 -0.6201831 0.3787773 -0.6743873 -0.6338214 0.01399374 -0.09352231 -0.9955189 0.3850123 -0.6378247 -0.6670421 0.3735777 -0.6570481 -0.6547729 0.1442021 -0.2502208 -0.9573899 0.2689699 -0.5236918 -0.8083329 0.2713528 -0.4233413 -0.8643783 0.2919685 -0.4866935 -0.823337 0.3770555 -0.6800788 -0.6287465 0.3166559 -0.7085635 -0.6306084 0.1388953 -0.4098048 -0.9015365 0.3634337 -0.7259598 -0.5838651 0.3534352 -0.7184734 -0.5990656 0.3289272 -0.7020253 -0.6316387 0.003742218 0.09547495 -0.9954248 0.1588364 -0.484108 -0.860471 0.2277657 -0.5977793 -0.7686239 0.0222063 0.9996342 -0.01544052 -0.02497243 0.9990541 -0.03559809 0.01248633 0.9988811 -0.04561549 0.01030063 0.9968045 -0.07921391 0.01094794 0.9968021 -0.07915741 0.01123374 0.98633 -0.1643992 -0.06065958 0.9840716 -0.1671031 -0.9996669 0 0.0258134 -0.9996572 -1.13005e-5 0.02618515 -5.75422e-4 1.24955e-5 0.9999999 -1.93148e-6 -6.84218e-5 1 0.3209202 0.8886115 -0.3276886 0.112021 0.9283099 0.354531 0.07761293 0.9395487 0.3335037 0.08252674 0.9441809 0.318923 0.05122739 0.9877606 0.1473255 0.05465447 0.9903305 0.1275088 0.04515594 0.9917449 0.1200131 0.03274762 0.9936232 0.1078914 0.02816277 0.9985355 0.04619383 0.02490764 0.9981622 0.05524581 0.01233994 0.9991 0.04058223 0.01840621 0.9993479 0.03106307 0.006324529 0.9984199 -0.05583816 0.01745796 0.9980731 0.05954283 0.01289933 0.9986765 0.0497896 -0.8825613 0.469262 -0.02964431 -0.9026442 0.4291476 -0.03264844 0.3606606 -0.4854499 -0.796406 0.2774605 -0.3438385 -0.8971015 0.2744469 -0.5682841 -0.7757139 0.2227932 -0.3796685 -0.8978948 0.1856234 -0.2271157 -0.9560139 0.1354847 -0.3590762 -0.9234221 0.08675754 -0.2667567 -0.959851 0.02739018 -0.3308128 -0.9432989 0.03254735 -0.3772703 -0.9255312 -0.895818 -0.1280291 -0.4255806 -0.6991375 -0.1469776 -0.6997175 -0.6991608 -0.1469859 -0.6996924 -0.4501845 -0.1292207 -0.8835361 -0.1549112 -0.1391731 -0.9780765 -0.2243966 -0.1501995 -0.9628531 0.2243964 -0.1501998 -0.9628532 0.1549112 -0.1391731 -0.9780765 0.4501852 -0.1292206 -0.8835357 0.7130972 -0.1478179 -0.6853045 0.7125845 -0.1476249 -0.6858792 0.9359706 -0.1320796 -0.3263651 0.9650263 -0.1443667 -0.2188209 0.9667397 -0.1489155 -0.207939 0.9861716 -0.133462 -0.09825354 0.9880425 -0.1432799 -0.05694627 0.9909934 -0.1329035 0.01639562 0.9881201 -0.1427412 0.05695241 0.9824922 -0.1326385 0.1308283 0.9640861 -0.1508269 0.2186076 0.9518437 -0.1324852 0.27648 0.7208975 -0.1385685 0.6790476 0.7432709 -0.1457133 0.6529287 0.3817465 -0.1506272 0.9119107 0.4518935 -0.1387597 0.881214 0.1514453 -0.128155 0.9801228 -0.1550868 -0.1391768 0.9780481 -0.1259093 -0.1437551 0.9815708 -0.4495718 -0.1391734 0.8823356 -0.4495733 -0.1391732 0.8823348 -0.7467868 -0.1501286 0.6478973 -0.7026001 -0.1390992 0.6978571 -0.8908851 -0.1314253 0.4348002 -0.9659168 -0.1440167 0.2150908 -0.9647081 -0.1397297 0.2231903 -0.9891554 -0.1402338 0.04365867 -0.9891145 -0.1404119 0.04401385 -0.9884762 -0.1331466 -0.07202017 -0.9844731 -0.1428766 -0.1019751 -0.9661355 -0.1465548 -0.2123771 -0.9623821 -0.1349216 -0.2358323 0.3149911 -0.08732545 -0.9450688 0.2961204 -0.0748803 -0.952211 0.1602451 -0.09139907 -0.9828367 0.1630677 -0.08937412 -0.9825586 0.05300122 -0.08566457 -0.9949133 0.05353337 -0.08545666 -0.9949027 -0.96259 -0.08001071 -0.25888 -0.9680255 -0.09599661 -0.2317572 -0.9932478 -0.07903826 -0.08492296 -0.9948236 -0.09427136 -0.03793299 -0.9958835 -0.08154511 0.0395804 -0.9894732 -0.09708631 0.1073178 -0.9826951 -0.08083742 0.1666603 -0.9502254 -0.08518886 0.2996909 -0.9560555 -0.09333479 0.2779327 0.05300152 -0.08566409 0.9949134 0.05349713 -0.08547282 0.9949033 0.1736904 -0.07656461 0.9818195 0.1505897 -0.0889604 0.9845856 0.282925 -0.1007373 0.9538373 0.3356942 -0.07414782 0.9390483 0.2916097 -0.9565373 -3.51594e-4 0.2859933 -0.9582315 7.0238e-4 -0.5412681 -0.1050074 0.8342676 -0.5409735 -0.1049184 0.8344698 -0.5456383 -0.1049118 -0.831428 -0.5547373 -0.1077817 -0.8250149 -0.06037384 -0.986689 -0.1509967 -0.1495874 -0.9792764 -0.1365336 -0.1286064 -0.98345 -0.1276188 -0.1285043 -0.9835339 -0.127074 -0.06287044 -0.983492 -0.1696784 -0.05176115 -0.9928466 -0.107594 -0.02255207 -0.9862632 -0.1636351 -0.003011345 -0.9943842 -0.1057882 0.0140531 -0.9965866 -0.0813505 0.007941246 -0.9932974 -0.1153136 -0.08069986 -0.9943789 -0.06854343 -0.1395666 -0.9878468 -0.06840938 -0.0717234 -0.9962798 -0.04777425 -0.01387214 -0.9996464 -0.02268433 0.007497549 -0.9999647 0.003830909 -0.06641733 -0.9955729 0.06650829 -0.07063114 -0.9961156 0.05258339 -0.1466936 -0.9878516 0.05128598 -0.1471725 -0.9876524 0.05369484 -0.1316487 -0.9899691 0.05128216 -0.1277619 -0.9910914 0.03761392 -0.05903571 -0.9959151 0.06832367 -0.01987999 -0.9995089 0.02422505 0.01106685 -0.9996013 0.02597773 0.01085013 -0.9993336 0.03485566 -0.07618218 -0.9848562 0.1557387 -0.1402677 -0.9781202 0.1536422 -0.06548613 -0.9893046 0.1303387 -0.008668839 -0.9906296 0.1363009 -0.006555557 -0.9937729 0.111232 0.02076798 -0.9930791 0.1155976 0.02061331 -0.9961417 0.08530443 -0.06794601 0.9945313 0.07931596 -0.07809519 0.9963997 0.03300046 -0.1395971 0.989726 0.03090572 -0.1295347 0.9886467 0.0761485 -0.06079387 0.9959549 0.06616663 -0.06255012 0.9963215 0.05857527 -0.01797604 0.9998293 0.004275023 -0.01220875 0.9994047 0.0322684 0.01741695 0.9995881 0.02280914 0.01854121 0.9995751 0.02249103 0.01664674 0.999831 0.007808506 0.02406096 0.9995139 0.01982319 -0.07628887 0.9849418 0.1551445 -0.1441371 0.9774678 0.1542113 -0.1488745 0.9811843 0.1229392 -0.1234285 0.9858611 0.1133291 -0.06209462 0.9948598 0.07998907 -0.01254594 0.9802094 0.1975659 -4.28771e-4 0.9971933 0.07486909 0.02400684 0.9915158 0.1277502 0.02707618 0.99831 0.05142194 -0.07540619 0.6267864 0.7755339 -0.1442571 0.6151988 0.7750616 -0.1398139 0.639224 0.7562043 -0.136515 0.6200777 0.7725718 -0.04581481 0.6519397 0.7568856 -0.03706181 0.6327424 0.7734751 0.06059747 0.6695431 0.7402973 0.0662437 0.6584361 0.7497158 0.1608979 0.7094172 0.6861773 0.2309122 0.7033234 0.6723212 0.2174147 0.861786 0.4583185 0.2380027 0.785018 0.571928 -0.07217884 0.6998099 0.7106733 -0.06936997 0.7073218 0.7034798 -0.1441351 0.7148235 0.6842898 -0.1475484 0.7033072 0.6954054 -0.1285103 0.7185873 0.6834599 0.1279234 0.7890411 0.6008743 0.2016789 0.8310758 0.5183036 0.1438083 0.912985 0.3818085 0.1577255 0.912027 0.378589 0.1479468 0.955219 0.2562587 -0.0655086 0.7958266 0.6019708 -0.07223784 0.7762854 0.6262289 -0.1404383 0.7716807 0.6203112 -0.1394554 0.7780269 0.6125573 -0.04448199 0.7667428 0.6404116 -0.04693901 0.7590824 0.6493002 0.05295193 0.764024 0.6430113 0.03493392 0.7992172 0.6000262 0.1253686 0.8139466 0.5672511 0.09728646 0.8666216 0.48939 0.1567319 0.8849467 0.4385253 0.1156091 0.9340923 0.3377963 0.12718 0.9334068 0.3355248 0.1219304 0.9659579 0.228163 -0.07674866 0.8389878 0.5387108 -0.1478538 0.8395035 0.522851 -0.1341251 0.8032239 0.5803809 -0.06341046 0.8462114 0.5290609 0.02446526 0.8723172 0.4883279 0.01792657 0.8264756 0.5626872 0.06793671 0.8731691 0.4826599 0.07988142 0.9228202 0.3768581 0.08906489 0.9166452 0.3896526 0.1108228 0.942795 0.3144139 0.09323465 0.9551534 0.2810506 0.09607684 0.976437 0.1932356 -0.07035166 0.8824968 0.465027 -0.07816904 0.8977214 0.4335736 -0.1414939 0.8882763 0.4369723 -0.1399409 0.8918774 0.430083 -0.1267777 0.867769 0.4805253 -0.05915188 0.8881793 0.4556739 -0.04687333 0.8684732 0.4935151 0.004677355 0.9202967 0.3911934 0.05091398 0.9396007 0.3384649 0.02248007 0.90121 0.4327996 0.08342468 0.9324549 0.3515228 0.05383795 0.957975 0.2817544 0.08340167 0.9710661 0.2237743 0.05503094 0.9892627 0.1353921 -0.06859165 0.931392 0.3574973 0.04157018 0.9767134 0.2104828 0.05902409 0.976741 0.2061389 -0.06762588 0.9703746 0.2319482 -0.07719314 0.9585332 0.274327 -0.1462468 0.9487753 0.2800668 -0.1439743 0.9519238 0.2703934 -0.1277822 0.9510048 0.2815346 -0.130196 0.9542846 0.2690536 -0.05398154 0.96263 0.2653857 -0.05015337 0.959114 0.2785411 0.008227765 0.9704164 0.2412973 0.009905576 0.969038 0.246713 0.04084461 0.9832349 0.17771 0.0377438 0.9848552 0.1692209 0.0411446 0.992844 0.1121073 -0.0611658 0.3715903 -0.9263797 -0.1457291 0.3437188 -0.9276964 -0.04468798 0.3511624 -0.9352476 0.2435131 0.3766611 -0.8937717 -0.06792974 0.9958744 -0.06016534 -0.1493018 0.9868451 -0.06201577 -0.1197176 0.9914255 -0.05237549 -0.0176171 0.9980874 -0.05925667 -0.0806725 0.9874216 -0.1359809 -0.1386449 0.9812985 -0.133532 -0.1322948 0.9786043 -0.1575807 -0.05822432 0.9861189 -0.1554974 -0.05561238 0.9879437 -0.1444799 -0.002188205 0.9900459 -0.1407279 -0.06441009 0.9701385 -0.2338433 -0.0711081 0.9637197 -0.2572706 -0.1477206 0.9559448 -0.2536692 -0.1439853 0.9606023 -0.2377218 -0.1232346 0.9634962 -0.2376731 -0.004650712 0.9586522 -0.2845425 0.01470434 0.9779178 -0.2084721 -0.07691866 0.9311203 -0.3565087 -0.1441019 0.924641 -0.3525248 -0.1468829 0.9175333 -0.3695374 -0.1301478 0.9223359 -0.3638105 -0.128413 0.9169433 -0.3777897 -0.06422495 0.937991 -0.3406584 -0.05379414 0.9272716 -0.3705045 0.007024288 0.9481588 -0.3177193 -0.06378108 0.900389 -0.4303854 -0.07031184 0.8893954 -0.4516991 -0.1406816 0.883704 -0.4464035 -0.1365604 0.868752 -0.4760476 -0.05006134 0.8708324 -0.4890244 -0.00235325 0.9210772 -0.3893731 0.05124521 0.9232882 -0.3806746 0.0533629 0.9321369 -0.3581528 -0.0762251 0.8344283 -0.5458199 -0.1479706 0.8186702 -0.5548729 -0.1339344 0.858716 -0.4946398 -0.060723 0.8331611 -0.5496866 0.02436602 0.8574236 -0.5140341 0.02929586 0.8523987 -0.5220711 0.09415304 0.8644518 -0.49382 -0.0631901 0.7913061 -0.6081463 -0.06895339 0.778473 -0.6238793 -0.1385315 0.7618359 -0.6327837 -0.1404907 0.7809734 -0.6085582 -0.04590845 0.7807423 -0.6231644 0.09385037 0.8729289 -0.4787353 -0.07517486 0.7064737 -0.7037356 -0.1436905 0.707238 -0.6922193 -0.1404761 0.6753232 -0.7240201 -0.05317956 0.7056717 -0.7065406 -0.06088465 0.7296344 -0.6811217 0.04871296 0.7366846 -0.6744797 0.04064607 0.7495722 -0.6606736 0.1163778 0.7618324 -0.6372345 0.1502189 0.7263795 -0.6706766 0.1609093 0.7918593 -0.5891241 -0.06369078 0.654604 -0.7532842 -0.07103323 0.6275696 -0.7753132 -0.1440213 0.6232451 -0.7686504 -0.1454183 0.608003 -0.7805036 -0.0570448 0.6129965 -0.7880237 -0.05918419 0.6184887 -0.7835617 0.05263072 0.6359304 -0.7699498 0.04701632 0.6474336 -0.7606703 0.1327779 0.6702582 -0.7301534 0.1335923 0.6691831 -0.7309905 0.200521 0.6762965 -0.708812 0.1837242 0.7013838 -0.6886988 -0.06537514 0.5204337 -0.8513959 -0.07081401 0.5417508 -0.8375509 -0.1423508 0.5370457 -0.8314555 -0.0753228 0.4353944 -0.8970832 -0.1450174 0.4655084 -0.8730818 -0.1424087 0.4341741 -0.8895013 -0.05681592 0.4802142 -0.8753092 -0.05719447 0.4810936 -0.8748016 0.05825513 0.4977882 -0.8653401 0.06143999 0.4912036 -0.8688753 0.1576273 0.5064067 -0.8477653 0.1577806 0.5061728 -0.8478765 0.2204937 0.5430777 -0.8102155 0.2397349 0.5055314 -0.8288337 -0.08321619 0.2756214 -0.9576575 -0.1396838 0.2676232 -0.9533448 -0.057033 0.2836679 -0.957225 0.0720461 0.2927755 -0.9534631 0.07627403 0.2828035 -0.9561405 0.1776935 0.3158518 -0.9320208 0.1893181 0.2878527 -0.9387756 0.2646363 0.3101693 -0.913106 0.2645332 0.2285426 -0.9369047 -0.08509677 -0.9624102 -0.2579252 -0.1430589 -0.9555944 -0.2576308 -0.1384462 -0.9520401 -0.2728599 -0.11875 -0.9526005 -0.2800905 -0.007547557 -0.9831455 -0.182669 0.02364492 -0.9935454 -0.1109437 0.01280403 -0.9829798 -0.1832674 -0.06639844 -0.9681457 0.2414232 -0.07116776 -0.9634734 0.2581748 -0.1476154 -0.9555745 0.255122 -0.1482828 -0.9546788 0.2580711 -0.1298216 -0.9579713 0.2558075 -0.127628 -0.9604489 0.2474856 -0.05418688 -0.9598965 0.2750684 -0.05192399 -0.9635711 0.2623636 0.002399563 -0.9669527 0.2549446 0.009866714 -0.9807925 0.1948043 0.04155832 -0.9747694 0.2193119 0.04144805 -0.991481 0.1234809 0.04144459 -0.9914871 0.1234331 0.0220775 -0.9963289 -0.08271312 0.03007423 -0.9989851 -0.03353542 0.03046721 -0.9991205 -0.0288096 0.02521264 -0.99945 -0.02154356 0.02150058 -0.9983397 -0.05343878 0.0218091 -0.999609 0.01749998 0.02061158 -0.9994171 0.0272147 0.01981854 -0.9990562 0.03865224 0.01980412 -0.9990392 0.03909838 0.01909482 -0.999814 0.002708375 0.0168941 -0.9998198 0.008668005 0.01630705 -0.9997432 0.01573669 -0.006011128 0.7799037 0.6258709 -0.00379163 0.7798291 0.625981 -0.003530144 0.7793346 0.6265981 3.07207e-4 0.3028808 0.9530284 -0.00126034 0.3098197 0.9507946 9.60688e-5 0.3099987 0.950737 -0.006582975 0.2987451 0.9543102 -4.80564e-4 0.8159484 0.5781245 -2.22798e-4 0.8161704 0.5778114 -0.001247823 0.1941705 0.980967 -0.00692147 0.1908737 0.9815903 0.00433892 0.1863087 0.9824817 -5.24029e-4 0.1794155 0.9837732 0.002964615 0.6329053 0.7742237 -0.002599418 0.6358284 0.7718262 0.0118674 0.6452203 0.7639045 -0.01053601 0.6407476 0.7676793 -3.14704e-4 0.6264643 0.7794502 -5.4743e-5 0.6292791 0.7771795 0 0.7762469 0.6304292 0 0.7762473 0.6304287 1.23692e-7 0.7762481 0.6304276 0.005592703 0.720947 0.6929677 0 0.7221452 0.6917415 -0.5591644 0.8286977 -0.02440077 -0.5588402 0.828859 -0.02627712 -0.5588615 0.8288447 -0.0262748 -0.5591729 0.8286401 -0.02610009 -0.560108 0.8280455 -0.02489674 -0.5619682 0.8266241 -0.02974069 -0.5588476 0.828854 -0.02627825 -0.5589581 0.8287824 -0.02618283 -0.5590003 0.8287546 -0.02616411 -0.5589611 0.8287805 -0.02617937 -0.5589633 0.8287792 -0.02617561 0.06972742 0.9972227 -0.02617555 0.06967371 0.9972259 -0.02619481 0.06950438 0.9972375 -0.02620559 0.06973201 0.9972187 -0.026313 0.06974339 0.9972218 -0.0261662 0.07063436 0.9971821 -0.02527302 0.06937551 0.997215 -0.0273745 0.06973236 0.9972223 -0.02617782 0.069839 0.9972128 -0.02625268 0.0697323 0.9972223 -0.02617675 0.06973338 0.9972221 -0.02618223 0.06991505 0.9972127 -0.02605229 0.06967687 0.9972336 -0.02589261 -0.006741404 0.01734018 0.999827 2.63599e-5 -6.93497e-5 1 1.56186e-4 -1.59505e-4 1 0 -5.27366e-4 1 -2.91773e-5 -0.001387536 0.9999991 0.3408556 0.3135421 -0.8862894 0.3460124 0.3226062 -0.8810226 0.3693388 0.2551479 -0.8935818 0.3466434 0.3272641 -0.8790544 0.3835221 0.235469 -0.8930091 0.38249 0.1577242 -0.910398 -0.8671144 0.3447048 -0.3595712 -0.4570992 0.828414 -0.323714 -0.9374902 0.1050827 -0.3317676 0.1933272 0.6483141 -0.7364194 -0.8784431 0.3412312 -0.3345133 -0.43497 0.6795192 -0.5908086 -0.130977 0.8156837 -0.563476 -0.3042648 0.5306466 -0.7910987 -0.3235343 0.5557937 -0.76578 0.1358011 0.3368324 -0.9317199 0.1348736 0.3681719 -0.9199232 -0.7317036 0.2483297 -0.6347774 0.4193425 0.9032963 -0.09059619 0.5957604 0.7932608 -0.1257263 0.5966452 0.7931469 -0.1221993 -0.6840782 0.2482678 -0.6858572 -0.1848953 0.2850248 -0.9405183 -0.1848316 0.2849584 -0.9405509 -0.1285019 0.1962655 -0.9720942 -0.4037314 0.1174396 -0.9073087 0.4346441 0.8731024 -0.2208546 -0.4834269 0.1346774 -0.8649628 -0.1820113 0.9391291 -0.2913905 -0.325368 0.06334239 -0.9434636 -0.04825335 -0.06421351 -0.996769 -0.8211864 0.5155416 -0.244683 -0.2122291 0.6203557 -0.7550614 0.5388695 0.693198 -0.47864 0.05854201 0.8422918 -0.5358334 -0.2983624 0.9080275 -0.294051 0.3884801 0.7662758 -0.5117664 0.3872584 0.79514 -0.4666727 -0.2622134 0.7872573 -0.5580953 -0.8489974 0.4948567 -0.1852574 0.5408941 0.6941215 -0.4750041 -0.2158171 0.6457121 -0.7324472 0.3248237 0.5937997 -0.7361329 -0.6835887 0.3714122 -0.6282989 -0.7091435 0.3746572 -0.5972834 -0.0958507 0.3156302 -0.9440287 -0.8171249 0.001995682 -0.5764574 -0.01318961 -0.07333195 -0.9972204 -0.1352314 0.3835248 -0.9135761 0.3996454 0.4667726 -0.7889278 0.01665818 0.9582502 -0.2854456 0.2257255 0.3308276 -0.9162975 0.3935143 0.4622591 -0.7946465 -0.4606342 0.2225164 -0.8592453 0.2874259 0.5418906 -0.7897727 -0.5399489 0.2546992 -0.8022366 -0.08385735 0.8387812 -0.5379723 -0.2374978 0.05437225 -0.9698652 0.2322019 0.8172692 -0.5274026 -0.1166032 0.9549574 -0.2728738 -0.08491122 0.6837743 -0.7247364 -0.08543741 0.6661146 -0.7409398 -0.6964004 0.6521047 -0.2996432 -0.03488278 0.4147261 -0.9092774 -0.7484661 0.2686926 -0.6063026 -0.4684479 0.6510307 -0.5972569 -0.03670984 0.2815093 -0.9588561 -0.7299416 0.5942594 -0.3376998 0.2171412 0.9416875 -0.2570495 -0.4859265 0.3567079 -0.7978941 -0.4847779 0.3559891 -0.7989131 -0.3159164 0.1875749 -0.9300605 0.4462398 0.736313 -0.5086386 -0.2830786 0.1677438 -0.9443138 0.07712531 0.9589652 -0.2728324 -0.1040538 0.008213639 -0.9945377 -0.03941649 -0.0368908 -0.9985417 0.06108909 0.7028816 -0.7086788 0.06720209 0.666838 -0.7421664 -0.5433825 0.7787641 -0.3134674 -0.4077042 0.4567891 -0.790646 0.04097014 0.3634627 -0.9307075 0.05343663 0.2821852 -0.9578707 -0.3229309 0.7394121 -0.59075 -0.611661 0.5042629 -0.6095817 -0.6014344 0.726406 -0.3325822 -0.4031821 0.4479755 -0.7979738 0.2599084 0.9563247 -0.1337562 -0.2349249 0.233713 -0.9434981 -0.2376472 0.2388439 -0.9415293 -0.04968529 -0.006521165 -0.9987437 0.2333034 0.8240014 -0.5163248 -0.3707759 0.8762675 -0.3077023 0.2319507 0.8328944 -0.5024799 -0.9327085 0.3534699 -0.07151228 -0.914879 0.3715821 -0.1578716 0.2049937 0.6713503 -0.7122263 0.9996576 -4.97687e-4 -0.02616369 0.9996466 2.61491e-4 -0.02658343 0.9996463 2.74532e-4 -0.02659642 0.9995971 1.03989e-4 -0.02838557 0.9996577 -9.31861e-7 -0.02616328 0.9995438 -0.002294063 -0.03011691 0.99965 7.98187e-5 -0.02645778 0.9996574 -2.66317e-5 -0.02617394 0.9996551 -4.31194e-6 -0.0262627 0.9996564 -1.23591e-5 -0.02621418 0.9996574 9.79484e-6 -0.02617514 0.9996573 -1.18608e-5 -0.02617883 0.9996567 -1.28612e-5 -0.02619934 0.9996575 -2.89213e-6 -0.02617579 -0.006352245 0.5870432 0.8095307 -0.00390172 0.5885453 0.8084548 1.59893e-4 0.5822621 0.8130012 0.01355695 0.7766798 0.6297498 0.002120196 0.7725337 0.6349703 -0.006687939 0.777607 0.628715 0.008980095 0.7256014 0.6880567 0.01102113 0.7253448 0.6882975 0.007081151 0.7236192 0.6901631 -0.01340162 0.7160676 0.6979023 -0.001636862 0.7276388 0.6859586 0.0048002 0.6607612 0.7505809 -0.00150305 0.6602045 0.7510845 -0.02046543 0.6841601 0.7290447 0.1139153 -0.5950036 -0.7956092 0.1532694 -0.7384634 -0.6566433 0.1642473 -0.7098174 -0.6849688 0.2661451 -0.5989018 -0.7553036 5.40391e-4 -0.2286318 -0.9735129 -0.006516754 -0.2526716 -0.9675303 -0.001701474 -0.5204837 -0.8538699 2.88617e-4 -0.5135452 -0.8580626 -0.001067698 -0.7408164 -0.6717069 0.00503242 -0.7670872 -0.6415233 -0.005047082 -0.8640667 -0.503352 0.00827372 -0.9290295 -0.3699133 -0.0110737 -0.9737971 -0.2271491 0.01199239 -0.9975716 -0.06860929 -0.01281762 -0.9963709 0.08414793 0.01308423 -0.9806702 0.1952298 0.02172362 0.4879392 -0.8726072 -0.02270108 0.3864899 -0.9220142 0.01929485 0.2431764 -0.9697902 -0.015006 0.09000754 -0.9958281 0.008216083 -0.0433554 -0.999026 1.956e-5 2.79943e-4 -1 0.004101634 -9.67261e-5 -0.9999917 0.009435594 -2.20109e-4 -0.9999555 0.6977591 -9.57074e-4 -0.7163319 0.7157099 -1.19613e-4 -0.6983978 0.9996575 7.86476e-6 -0.02616953 0.9996572 -1.54754e-5 -0.02618658 0.9996572 1.5434e-5 -0.02618157 0.9996569 -4.27654e-6 -0.026196 0.9996577 1.77009e-5 -0.02616304 0.9996649 -7.02083e-4 -0.0258786 0.999658 5.20326e-7 -0.02615541 0.9996573 5.17061e-7 -0.02617633 0.9996573 -1.2184e-6 -0.02617907 0.9996557 2.16466e-5 -0.02623832 0.9997746 1.96116e-4 -0.02123099 0.9996576 8.00081e-6 -0.02616882 0.9895719 -0.1414111 -0.02739518 -0.7910153 -0.611199 -0.02703136 -0.7977544 -0.6024098 -0.02627539 -0.003020226 0.6636028 0.7480791 -0.007473886 0.6603056 0.7509598 0.01432144 0.6258569 0.7798065 7.98435e-4 0.6322572 0.7747582 0.01184302 0.6444254 0.7645755 0.006248533 0.5856686 0.8105267 -4.81715e-4 0.5891035 0.8080576 0.02457636 0.51012 0.8597521 -0.001890003 0.5308709 0.8474507 -7.22688e-4 0.5322269 0.8466015 -0.02010387 0.5462526 0.8373792 0.001891016 0.5308714 0.8474503 -0.02457422 0.5101203 0.8597521 7.23859e-4 0.5322273 0.8466012 0.02054625 0.5465688 0.8371621 0.006638586 0.471078 0.8820666 7.19601e-4 0.4685809 0.8834204 -0.003409028 0.4748229 0.8800747 -0.006638765 0.4710787 0.8820662 -7.18596e-4 0.4685818 0.8834199 0.003409028 0.4748227 0.880075 -0.005337059 0.3942742 0.9189774 -0.002476036 0.3951036 0.9186334 -2.55271e-4 0.4087893 0.9126288 -0.002175807 0.4109929 0.911636 0.005339682 0.394274 0.9189774 0.002476036 0.395103 0.9186335 0.002175807 0.4109932 0.9116359 2.58991e-4 0.4087896 0.9126287 0.006582975 0.2987455 0.9543101 -3.07207e-4 0.3028806 0.9530286 -9.49756e-5 0.3099994 0.9507368 0.00126034 0.30982 0.9507944 -0.7084599 0.7048495 -0.03566265 -0.7593517 0.6505196 -0.01447182 -0.8359072 0.5483343 -0.02426719 -0.8158467 0.5772647 -0.0340569 -0.8920811 0.4509783 -0.0284577 -0.8957453 0.4438496 -0.02526068 -0.9495691 0.3126621 -0.02368497 -0.9572592 0.2874571 -0.03199142 -0.9878261 0.1538876 -0.02276879 -0.9941532 0.1029938 -0.03243094 -0.999477 0.02413552 -0.02152341 -0.9967051 -0.0756182 -0.0293411 -0.9940208 -0.1064674 -0.02423524 -0.972847 -0.2300626 -0.02529764 -0.9771051 -0.2109292 -0.02783221 -0.9405334 -0.3386206 -0.02707898 -0.9412346 -0.3366382 -0.02742767 -0.8929965 -0.4494277 -0.02391862 -0.8505118 -0.5253326 -0.02560389 -0.869722 -0.4927294 -0.0283125 0.6365482 -0.7707942 -0.02612864 0.9945763 -0.1013739 -0.02326762 0.9993064 -0.02410095 -0.02839112 0.9994692 0.02343368 -0.02263677 0.9931814 0.1124813 -0.03064036 0.9878261 0.1538876 -0.02276879 0.9572592 0.2874568 -0.03199142 0.949569 0.3126626 -0.02368503 0.8920815 0.4509777 -0.02845752 0.8957451 0.4438499 -0.02526068 0.8158466 0.5772647 -0.03405684 0.8359076 0.5483336 -0.02426731 0.7593526 0.6505185 -0.01447218 0.7084597 0.7048497 -0.03566271 0.6703547 0.7417225 -0.02173274 0.6087521 0.7926924 -0.03255099 0.5602688 0.828226 -0.01185548 0.5026803 0.8637043 -0.03643488 0.3925359 0.9192825 -0.02890425 0.4103755 0.9117085 -0.0194835 0.2621459 0.9644034 -0.03472501 0.2841818 0.9584839 -0.02344095 0.1617593 0.986719 -0.01481968 0.08859276 0.9952362 -0.04069787 0.03555393 0.9992123 -0.01763027 -0.07915663 0.9963051 -0.03332489 -0.09821438 0.9948918 -0.02333223 -0.2126337 0.9767041 -0.02891474 -0.2234511 0.9744337 -0.02342349 -0.3346678 0.9418914 -0.02895218 -0.3523033 0.9356868 -0.01930218 -0.4605066 0.8871164 -0.03095358 -0.4662686 0.8842155 -0.02750575 -0.5723912 0.8197749 -0.01837021 -0.5991723 0.7998914 -0.03415465 -0.6703549 0.7417224 -0.02173274 2.35822e-4 0.07487833 0.9971927 -0.002981007 0.06764155 0.9977053 1.03176e-4 0.07487189 0.9971932 2.04998e-6 0.07590603 0.997115 -5.40076e-4 0.07570606 0.99713 5.05879e-4 0.07527947 0.9971624 -1.73665e-4 0.07485258 0.9971946 -2.82641e-4 0.07495224 0.9971871 -0.003778874 0.09278613 0.995679 0.004509389 0.1930915 0.9811704 0.003203749 0.200763 0.9796347 0.001593351 0.2009909 0.9795919 -1.4939e-5 6.3553e-6 1 7.24124e-5 -3.71608e-4 1 0 0 1 0 2.94595e-7 1 -1.63152e-7 0 1 0 0 1 0 0 1 0.677399 0.7274605 0.1092331 0.7144302 0.6987476 0.03662467 0.7147758 0.6983914 0.03667658 -0.9996574 -7.77344e-7 0.02617603 -0.9996574 0 0.02617526 -0.9996575 6.27942e-6 0.02617573 0.02101558 0.9994364 0.02617686 0.02101558 0.9994364 0.02617675 -0.6991457 0.7140004 0.03740102 -0.6991501 0.7139965 0.03739285 -0.6991461 0.714 0.03740119 0.722492 -0.6913691 -0.003760874 0.7078503 -0.7063598 0.001992285 0.8003382 -0.5994942 0.008086979 0.83261 -0.5536459 -0.01539301 0.8705769 -0.4919862 0.006756365 0.917449 -0.3976616 -0.01236253 0.9138424 -0.4060689 1.98917e-4 0.9595307 -0.2813585 0.01176244 0.8453427 0.5333152 0.03115838 0.8881466 0.4591701 0.0189343 0.9297051 0.3671089 0.02965784 0.9575085 0.2875836 0.02175402 0.9714689 0.2352125 0.03038537 0.9884334 0.1504055 0.01943671 0.9987602 0.0391941 0.03069055 0.9988249 0.03647142 0.03191882 0.9907755 -0.1338217 0.02134901 0.9850586 -0.1683588 0.03626269 0.9661302 -0.2575579 0.01601117 0.9344623 -0.3545268 0.03303176 0.9378759 -0.345954 0.02655065 0.8852146 -0.4645099 0.02501702 0.8795826 -0.4743519 0.0363993 0.7940782 -0.6075932 0.01644843 0.7848836 -0.6186964 0.03424441 0.7041846 -0.7100061 0.003933846 0.689499 -0.7224706 0.05125874 0.5640925 -0.825711 0.001020431 0.5551529 -0.8307633 0.04046851 0.4473378 -0.8942034 -0.01701146 0.4307982 -0.8966358 0.1022602 0.267583 -0.9614579 -0.06323009 0.2536607 -0.9546483 0.1558942 0.07593899 -0.9873886 -0.138914 0.04485493 -0.9360904 0.3488882 -0.07110053 -0.9387513 -0.3371809 -0.1264365 -0.923397 0.362425 -0.2692377 -0.9545072 -0.1281687 -0.2675855 -0.9614571 -0.0632323 -0.4307968 -0.8966369 0.1022577 -0.4473376 -0.8942035 -0.01701235 -0.5551536 -0.8307629 0.0404694 -0.5640915 -0.8257117 0.001020669 -0.6894986 -0.7224709 0.05125856 -0.7041847 -0.7100061 0.003934264 -0.7848834 -0.6186966 0.03424322 -0.7940793 -0.6075918 0.01644825 -0.8795813 -0.4743542 0.03639966 -0.8852153 -0.4645084 0.02501708 -0.9378755 -0.3459545 0.02655059 -0.9344627 -0.3545258 0.03303182 -0.9661306 -0.2575567 0.01601111 -0.9850586 -0.1683588 0.03626269 -0.9907754 -0.1338228 0.02134901 -0.9987602 0.03919404 0.03069055 -0.9988276 0.03635168 0.03197246 -0.9882965 0.1513209 0.01929312 -0.9714694 0.235213 0.03036797 -0.9573356 0.2881527 0.02182847 -0.9297046 0.36711 0.02965813 -0.8882235 0.4590214 0.01893168 -0.8453418 0.5333162 0.03116387 -0.7777419 0.6282623 0.02010488 -0.7160012 0.6974318 0.03051865 -0.6452026 0.7636917 0.02210706 -0.5645875 0.8248878 0.02830457 -0.5422146 0.8398345 0.02610367 -0.5444604 0.8383781 0.02617639 -0.548374 0.8358207 0.02626621 -0.5444488 0.8383855 0.02617698 -0.4538393 0.8907086 0.02584892 -0.4424266 0.8964284 0.02597957 -0.4538363 0.8907006 0.02617692 -0.4639929 0.8854383 0.02664047 -0.3459543 0.9378771 0.02649927 -0.3594877 0.9327451 0.02748262 -0.2802535 0.9596065 0.02476918 -0.179384 0.9834068 0.0270676 -0.138685 0.9900217 0.02497118 -0.03920054 0.9988494 0.02762866 0.05592405 0.998142 0.02418899 0.1332827 0.9906904 0.027718 0.2383465 0.9708514 0.02526807 0.2811937 0.9592663 0.02717089 0.3479068 0.9371839 0.02544009 0.4421011 0.8965903 0.02593421 0.4422037 0.8963167 0.03274703 0.4521153 0.8915595 0.02671247 0.564592 0.8248933 0.02805554 0.5461652 0.8372666 0.02623254 0.5443338 0.8384604 0.02617245 0.5445502 0.8383195 0.02618199 0.525465 0.8504492 0.02495676 0.6370754 0.770509 0.02123612 0.7160016 0.697432 0.03050166 0.7774366 0.628641 0.0200777 0.003153681 0.9999907 -0.002941489 7.36419e-4 0.9999987 -0.0014503 1.4771e-4 0.9999997 -9.29218e-4 -1.00517e-4 0.9999998 -6.40048e-4 -2.20437e-4 0.9999999 -4.31215e-4 -0.001541972 0.9999946 0.002903163 0.004431724 0.9998227 0.01830631 0.9928917 -0.1126306 0.03847652 0.9307636 -0.04401528 -0.3629627 0.8483664 -0.1141116 -0.5169651 0.5661591 -0.07470631 -0.8209037 0.5502513 -0.09024679 -0.8301079 0.460375 -0.09037494 -0.8831123 0.4371476 -0.07592862 -0.896179 0.3749003 -0.09259366 -0.9224296 0.3809034 -0.08935904 0.9202868 0.4572867 -0.0901274 0.8847407 0.4726603 -0.07939457 0.877661 0.5496953 -0.09260427 0.8302166 0.5653365 -0.08054894 0.8209181 0.8339712 -0.09334653 0.5438554 0.8364172 -0.0916481 0.5403766 0.9844531 -0.06637495 0.1626242 0.370545 -0.9288123 -0.002087712 0.3649686 -0.9310198 7.45071e-5 0.4670923 -0.8842087 -1.0866e-4 0.4682629 -0.883589 6.14108e-4 0.5083601 -0.8611445 5.26314e-4 0.5074185 -0.8616998 1.45449e-4 1 -5.66874e-6 1.65675e-6 1 0 0 1 -2.07038e-6 0 1 2.36145e-6 0 1 -3.19301e-6 3.28351e-6 1 2.36023e-6 1.03431e-6 1 -4.89729e-6 -7.24817e-7 1 -6.30943e-7 -1.88399e-6 1 0 2.48955e-6 1 2.34841e-6 1.35603e-6 1 3.18064e-6 -3.26202e-6 1 -2.50273e-6 1.67111e-6 1 -3.353e-6 -2.23886e-6 1 0 -1.37419e-6 1 0 1.43514e-6 1 -2.35706e-6 0 1 0 -1.60367e-6 1 1.22184e-6 4.21631e-7 1 -7.93131e-6 -2.50845e-6 1 -4.75279e-6 1.04489e-6 1 -2.38047e-6 -6.51187e-7 1 4.75832e-6 0 1 -8.98484e-7 -4.09934e-7 1 -4.55467e-6 1.25115e-7 1 2.37506e-6 -2.20845e-7 1 -1.06833e-6 -1.86909e-6 1 0 -1.82711e-6 1 0 2.19628e-7 1 0 4.5683e-7 1 0 -1.74329e-6 1 -1.06509e-6 -1.75279e-6 1 -2.34919e-6 6.42629e-7 1 2.44518e-6 -2.02351e-6 1 0 -1.60926e-6 1 0 -1.88419e-6 1 0 1.5991e-6 1 -4.71333e-6 0 1 2.83347e-6 2.90368e-6 1 2.38179e-6 -1.37531e-6 1 0 1.37009e-6 1 0 -1.86169e-6 1 0 -1.14527e-6 1 -8.42832e-6 0 1 5.90105e-7 -1.03439e-6 1 4.72301e-6 0 1 -4.14717e-6 0 1 0 -8.15053e-7 1 0 -6.42624e-7 1 3.56852e-6 0 1 2.14276e-6 -4.43856e-7 1 -5.55784e-6 2.55863e-6 1 0 -2.18308e-7 1 5.66037e-6 1.09118e-6 1 0 -3.42705e-6 1 2.90759e-6 2.88447e-6 1 -4.72383e-6 2.19625e-7 1 0 -1.5728e-7 1 0 -2.59144e-6 1 1.17861e-6 1.76559e-6 7.32375e-7 -1 0 1.76806e-6 -1 1.73078e-6 -2.10626e-6 -1 0 0 -1 8.51719e-7 2.58786e-6 -1 -8.4567e-6 0 -1 1.1497e-6 7.06897e-5 -1 0 5.76081e-5 -1 4.23917e-5 0 -1 0 -2.41344e-6 -1 9.21647e-6 3.38036e-6 -1 0 3.10327e-5 -1 2.87918e-5 1.50838e-4 -1 -9.50534e-6 1.93166e-6 -1 3.39172e-6 0 -1 -1.8546e-5 2.3342e-6 -1 -1.20236e-5 0 -1 8.13723e-6 1.419e-6 -1 9.27411e-6 0 -1 -4.23443e-6 0 -1 -5.79378e-6 0 -1 9.19415e-7 0 -1 5.15763e-6 -1.65595e-4 -1 -2.80399e-4 2.48325e-4 -1 -3.89343e-4 -5.03544e-4 -1 -1.55588e-5 -6.85054e-4 -0.9999995 7.56567e-4 3.91649e-6 -1 -3.40485e-6 3.13628e-6 -1 8.30082e-6 0 -1 6.90074e-6 5.10007e-6 -1 1.92952e-5 -1.73846e-6 -1 0 1.17042e-6 -1 -6.88042e-7 6.54388e-5 -1 -3.12142e-5 -5.87538e-5 -1 1.83388e-5 3.0033e-5 -1 9.81155e-5 8.88792e-5 -1 3.36725e-5 -1.62796e-6 -1 4.08231e-6 9.26648e-5 -1 9.54489e-5 -3.7797e-6 -1 0 -3.46832e-6 -1 0 -1.87014e-6 -1 6.85763e-6 -4.38074e-5 -1 4.49515e-5 2.81962e-5 -1 1.30893e-4 1.40658e-4 -1 -2.25435e-5 8.02172e-5 -1 1.4093e-5 -1.40203e-6 -1 -2.7226e-6 2.79263e-5 -1 5.13149e-5 -1.47858e-4 -1 7.8991e-6 -1.04564e-6 -1 -1.21999e-5 -5.50831e-7 -1 0 -1.19302e-6 -1 0 0 -1 1.20411e-5 -1.53869e-6 -1 -3.75027e-6 -5.71426e-5 -1 1.09326e-4 2.21407e-6 -1 0 2.75194e-6 -1 -4.33478e-6 -2.77625e-7 -1 -9.01264e-7 -1.87605e-4 -1 -1.18878e-4 -3.81782e-5 -1 -4.60111e-5 7.4428e-7 -1 0 -4.02968e-5 -1 -1.498e-4 1.153e-6 -1 0 -6.32918e-5 -1 -1.1378e-5 -3.41687e-5 -1 1.14613e-4 4.71143e-5 -1 -4.40243e-5 3.41119e-6 -1 0 1.72304e-6 -1 0 1.3483e-4 -1 -1.12195e-4 -8.53698e-5 -1 2.73956e-5 2.63085e-7 -1 0 1 -1.33925e-5 0 1 -6.99832e-6 0 1 1.33925e-5 0 1 -9.10469e-6 0 1 -2.34868e-6 0 1 3.02011e-6 0 1 -2.67852e-5 0 1 1.49395e-6 0 1 1.82094e-5 0 1 -2.26328e-6 0 1 5.01706e-6 0 1 2.12057e-6 0 0 -0.2393174 0.9709414 0 -0.2393137 0.9709424 0 0.992709 -0.1205363 0 0.2393174 0.9709414 0 0.9927086 -0.1205392 0 0.2393133 0.9709424 0 0.9350168 -0.3546037 0 0.464724 0.8854556 0 0.4647233 0.885456 0 0.9350162 -0.3546053 0 0.6631223 0.7485111 0 0.8229811 -0.5680687 0 0.6631233 0.7485103 0 0.8229833 -0.5680656 0 0.8229824 0.5680669 0 0.8229821 0.5680674 0 0.6631223 -0.7485111 0 0.6631233 -0.7485103 0 0.9350162 0.3546053 0 0.9350168 0.3546037 0 0.4647225 -0.8854564 0 0.4647248 -0.8854552 0 0.9927089 0.1205373 0 0.9927088 0.1205382 0 0.2393137 -0.9709424 0 0.2393169 -0.9709416 0 -0.2393137 -0.9709424 0 -0.2393174 -0.9709414 0 -0.4647213 -0.8854571 0 -0.4647225 -0.8854565 0 -0.6631228 -0.7485107 0 -0.6631223 -0.7485111 0 -0.8229852 -0.568063 0 -0.8229843 -0.5680641 0 -0.9350162 -0.3546053 0 -0.992709 -0.1205363 0 -0.9927089 -0.1205373 0 -0.992709 0.1205363 0 -0.9927089 0.1205373 0 -0.9350162 0.3546053 0 -0.8229857 0.5680624 0 -0.8229839 0.5680648 0 -0.6631228 0.7485107 0 -0.6631223 0.7485111 0 -0.4647228 0.8854563 0 -0.4647209 0.8854572 -1.10731e-4 0 1 -3.59626e-4 1.14275e-5 1 -0.1603788 -0.984225 0.07469844 -0.2832687 -0.9588015 0.02141702 -0.2616966 -0.9626371 -0.06960487 -0.4285473 -0.903266 0.0213949 -0.43888 -0.8975988 -0.04124087 -0.5824516 -0.8118182 0.04124808 -0.5923388 -0.805405 -0.02139437 -0.7236827 -0.6866137 0.06960666 -0.7100825 -0.7037929 -0.02141386 -0.7917542 -0.6059075 -0.0774703 -0.8257984 -0.5520205 0.115458 -0.8774259 -0.4656118 -0.1154538 -0.9087471 -0.4100942 0.07747018 -0.956241 -0.2917954 0.02141565 -0.9475581 -0.3119113 -0.0696069 -0.9902005 -0.1380053 0.02139282 -0.9912315 -0.1303949 -0.02139061 -0.9963906 0.04858618 0.06960815 -0.9994093 0.02688354 -0.0214129 -0.9856136 0.15161 -0.07470256 -0.9760375 0.2043776 0.07470405 -0.9451275 0.3259993 0.02141654 -0.9499272 0.3046203 -0.06960606 -0.8887736 0.4578461 0.0214135 -0.8766372 0.4760912 -0.06960386 -0.8222249 0.5642389 0.07470464 -0.790706 0.6076211 -0.07470369 -0.7236835 0.6866129 0.0696066 -0.7100825 0.7037929 -0.02141487 -0.5845391 0.8110835 0.0213896 -0.590753 0.8065689 -0.0213887 -0.4372432 0.899089 0.02138793 -0.4442957 0.8930257 0.07145959 -0.3329341 0.9380571 -0.09593677 -0.2606361 0.9587346 0.1135644 -0.1831853 0.9771062 -0.108197 -0.1071258 0.9903571 0.08784657 0.01798295 0.9996089 0.02141749 -0.005947709 0.9969033 -0.07841271 0.1607912 0.9867562 0.02141296 0.1818903 0.9808521 -0.06960612 0.2825419 0.9563414 0.07470726 0.3335403 0.9397717 -0.07470095 0.4276845 0.9014501 0.06688755 0.4515449 0.8915867 -0.03435766 0.5808717 0.8129982 0.04027622 0.5937066 0.8036731 -0.04027587 0.7084141 0.7049601 0.03436285 0.725167 0.6853168 -0.06688761 0.7917565 0.6059045 0.07746887 0.8219468 0.5640503 -0.07906216 0.8737881 0.4829543 -0.05700612 0.8844285 0.463181 0.0570054 0.9235488 0.3752422 0.07906359 0.9424094 0.3124366 -0.119365 0.9652093 0.2242059 0.1345472 0.9824432 0.12924 -0.1345457 0.9926937 0.04076319 0.1135676 0.9926938 -0.04076302 -0.1135672 0.9824432 -0.12924 0.1345457 0.9652088 -0.2242073 -0.1345479 0.9424097 -0.3124356 0.119365 0.9156297 -0.3850865 -0.1154589 0.871958 -0.4757719 0.1154578 0.8334978 -0.5407379 -0.1135086 0.7898549 -0.6069704 0.08784234 0.7077376 -0.7042854 0.05558472 0.7353283 -0.6754279 -0.05558288 0.6417974 -0.7618266 -0.08784234 0.5775855 -0.8084005 0.113507 0.5123808 -0.8501498 -0.1212908 0.4250508 -0.8958994 0.1292134 0.345526 -0.9315118 -0.1135674 0.2825418 -0.9563413 0.07470947 0.1587536 -0.98672 0.03436595 0.1838536 -0.9806751 -0.06689059 -0.005794227 -0.9977436 0.06689018 0.01998096 -0.9992098 -0.03436028 -0.1072412 -0.9914225 -0.07470488 -0.5925518 0.802104 -0.07423961 -0.5711638 0.8201351 0.03391641 -0.6644449 0.74347 0.07593089 -0.7231087 0.6804563 -0.118714 -0.7667279 0.6369312 0.08029311 -0.8382577 0.5438228 -0.03976076 -0.8393859 0.540615 -0.05627453 -0.9218902 0.3854061 -0.03975999 -0.9156531 0.3999984 0.03975832 -0.9758921 0.2146017 -0.03975933 -0.9723609 0.2300732 0.03975731 -0.9984253 0.05609768 0 -0.9973223 0.06479084 0.03391849 -0.9973223 -0.0647912 -0.03391873 -0.9984253 -0.0560975 0 -0.9723613 -0.230072 -0.03975707 -0.9758919 -0.2146028 0.03975945 -0.9156532 -0.3999983 -0.03975862 -0.9218904 -0.3854055 0.03975999 -0.839383 -0.5406195 0.05627417 -0.8382575 -0.543823 0.0397613 -0.7667257 -0.6369339 -0.08029329 -0.7231103 -0.6804547 0.1187137 -0.6644442 -0.7434707 -0.07592958 -0.5711625 -0.820136 -0.03391748 -0.592553 -0.8021032 0.07423937 -0.4263783 -0.9036709 -0.03975588 -0.4406771 -0.8967851 0.03975278 -0.2764246 -0.9593868 0.0562722 -0.2734674 -0.9610591 0.03976285 -0.1583352 -0.9841152 -0.08029508 -0.1091815 -0.9907736 0.08029514 -0.01122975 -0.9983521 0.05627566 0.01122981 -0.9983521 -0.05627703 0.1091808 -0.9907737 -0.08029496 0.1583366 -0.984115 0.08029526 0.273468 -0.9610589 -0.03976237 0.2764223 -0.9593875 -0.05627125 0.440676 -0.8967855 -0.03975361 0.4263792 -0.9036706 0.03975629 0.5925518 -0.802104 -0.07423961 0.5711638 -0.8201351 0.03391641 0.6644449 -0.74347 0.07593089 0.7231087 -0.6804563 -0.118714 0.7667279 -0.6369312 0.08029311 0.8382577 -0.5438228 -0.03976076 0.8393859 -0.540615 -0.05627453 0.9218902 -0.3854061 -0.03975999 0.9156531 -0.3999984 0.03975832 0.9758921 -0.2146017 -0.03975933 0.9723609 -0.2300732 0.03975731 0.9984253 -0.05609768 0 0.9973223 -0.06479084 0.03391849 0.9973223 0.0647912 -0.03391873 0.9984253 0.0560975 0 0.9723613 0.230072 -0.03975707 0.9758919 0.2146028 0.03975945 0.9156532 0.3999983 -0.03975862 0.9218904 0.3854055 0.03975999 0.839383 0.5406195 0.05627417 0.8382575 0.543823 0.0397613 0.7667257 0.6369339 -0.08029329 0.7231103 0.6804547 0.1187137 0.6644442 0.7434707 -0.07592958 0.5711625 0.820136 -0.03391748 0.592553 0.8021032 0.07423937 0.4263783 0.9036709 -0.03975588 0.4406771 0.8967851 0.03975278 0.2764246 0.9593868 0.0562722 0.2734674 0.9610591 0.03976285 0.1583352 0.9841152 -0.08029508 0.1091815 0.9907736 0.08029514 0.01122975 0.9983521 0.05627566 -0.01122981 0.9983521 -0.05627703 -0.1091808 0.9907737 -0.08029496 -0.1583366 0.984115 0.08029526 -0.273468 0.9610589 -0.03976237 -0.2764223 0.9593875 -0.05627125 -0.440676 0.8967855 -0.03975361 -0.4263792 0.9036706 0.03975629 0 1 0 0 -0.7071105 0.7071031 0 -0.7071022 0.7071114 0 0.7071086 0.707105 0 0.7071059 0.7071077 0 0.7071068 -0.7071068 0 0.7071077 -0.7071059 0 -0.7071031 -0.7071104 0 -0.7071096 -0.7071041 0.9999965 -1.82363e-4 -0.002674639 0.999994 -3.37323e-4 -0.003439664 1.0754e-4 -1 -5.19326e-4 -4.11773e-5 -0.9999992 -0.001253306 -0.9999943 6.00678e-4 0.003334641 -0.9999998 -1.82363e-4 -5.29112e-4 -0.7758123 0.6308654 0.01114761 -0.7641416 0.6447806 -0.01859545 -0.8904131 0.4538266 -0.03473109 -0.9585214 0.2849145 -0.007791101 -0.9480492 0.3168288 0.02867341 -0.997645 0.06814676 -0.007773876 -0.9983195 0.057428 0.007773995 -0.980575 -0.1955665 -0.01505255 -0.9837504 -0.1793736 0.007776081 -0.900376 -0.4350891 0.004548847 -0.9037781 -0.4276871 0.01639693 -0.7680456 -0.6403216 0.009715676 -0.7752082 -0.6316384 -0.009229063 -0.4594143 -0.8880347 -0.01825207 -0.4906922 -0.8713015 0.00741142 -0.3417599 -0.9393631 0.02823662 -0.2729358 -0.9616007 -0.02881145 -0.1096347 -0.993754 0.02081513 -0.1142578 -0.9933424 0.0146963 0.09744417 -0.9951621 -0.01253324 0.1333657 -0.9907658 0.02442836 0.2729479 -0.9616437 -0.02721869 0.3444207 -0.9384208 0.02721923 0.4594143 -0.8880346 -0.01825207 0.4908375 -0.8712187 0.00753206 0.7758461 -0.6308922 0.006167531 0.7663939 -0.6420853 -0.01915717 0.9058437 -0.4227988 -0.02623653 0.8879347 -0.4596094 0.01819735 0.9589684 -0.2821033 0.02823722 0.9798535 -0.1951969 -0.04225414 0.997613 -0.05461484 0.04225414 0.998997 0.03475391 -0.02823704 0.9772171 0.2120994 -0.007790744 0.9829611 0.182046 0.02542817 0.9061285 0.4229315 -0.007771253 0.8979493 0.4396796 0.0192036 0.7663938 0.6420853 -0.01915675 0.7760945 0.6305794 0.006858825 0.4660691 0.8838112 0.04071062 0.384736 0.922698 -0.02462875 0.2241667 0.9745197 -0.007791459 0.2538056 0.966921 0.02542829 0.005369126 0.9999554 -0.007772922 -0.005369126 0.9999554 0.007772922 -0.2567521 0.9663601 -0.01505279 -0.2407904 0.970546 0.007776975 -0.4678469 0.8837721 0.008140385 -0.4635393 0.8859738 0.01348447 2.36768e-6 0 1 -1.22085e-6 0 1 2.38334e-6 0 1 -3.97863e-6 0 1 5.36425e-6 0 1 4.75669e-7 0 1 2.12893e-7 0 1 -4.57398e-7 0 1 2.93681e-6 0 1 -1.82326e-6 0 1 2.56032e-6 0 1 -2.05899e-6 0 1 2.79859e-7 0 1 -1.03161e-6 0 1 1.65988e-6 0 1 -6.71032e-7 0 1 2.62203e-7 0 1 6.07768e-7 0 1 -3.12467e-7 0 1 0 0 1 4.88402e-7 0 1 -2.91463e-7 0 1 -1.54936e-7 0 1 -1.72618e-7 0 1 1.58105e-7 0 1 -2.1749e-7 0 1 -2.17272e-7 0 1 2.362e-7 0 1 0 0 1 2.7729e-7 0 1 -5.31227e-7 0 1 -6.13503e-7 0 1 1.9239e-6 0 1 -7.35139e-7 0 1 0 0 1 -4.5744e-7 0 1 -1.46963e-7 0 1 -0.7941264 0.607742 -0.003626704 -0.708833 0.7053728 -0.002207934 -0.7364647 0.6764724 0.002207875 -0.6442814 0.7647806 0.003497421 -0.5968464 0.8023514 -0.00259912 -0.4956333 0.8685309 -0.001363813 -0.5178737 0.855453 0.002658843 -0.3459307 0.9382563 -0.002658963 -0.3700221 0.929022 0.001363694 -0.2551758 0.9668913 0.002598881 -0.1842662 0.9828651 -0.004723608 -0.01999336 0.9997978 -0.002207994 0.01798772 0.9998363 0.001986324 0.109534 0.9939783 -0.00308156 0.1728381 0.9849395 0.004610121 0.2551755 0.96689 -0.003059506 0.3700221 0.929022 -0.001363873 0.3439285 0.9389911 0.002991318 0.5032101 0.8641612 0.002264559 0.5060656 0.8624936 0.001598775 0.6038404 0.7970986 -0.003236591 0.6519303 0.7582637 0.004803776 0.7149736 0.6991447 -0.003059446 0.7941322 0.6077448 6.45428e-4 0.7836151 0.6212358 0.003693699 0.9573647 0.2888568 -0.003845155 0.8709521 0.4913679 -7.18609e-5 0.881675 0.4718351 0.004602313 0.9271913 0.3745554 -0.004972696 0.9534575 0.3014505 0.00679785 0.9766416 0.2147673 -0.006797671 0.9916921 0.1284718 0.006475031 0.9992193 0.03906357 -0.005916774 0.9992193 -0.03906357 0.005916774 0.9916921 -0.1284718 -0.006475031 0.9766416 -0.2147672 0.006797671 0.9534575 -0.3014505 -0.006797909 0.9271912 -0.3745554 0.004972696 0.8898891 -0.4561672 -0.003026485 0.8701801 -0.4927231 0.003260314 0.8283235 -0.5602486 -0.00138545 0.8378631 -0.5458654 -0.004064321 0.7856511 -0.6186403 0.006049633 0.7282524 -0.685294 -0.004531025 0.6713738 -0.7411108 0.003497421 0.6038418 -0.7971011 -0.002207875 0.5806063 -0.8141839 9.77044e-4 -0.1095338 0.9939765 0.003627479 0.501816 -0.8649745 1.46931e-4 0.4976249 -0.8673917 0.001164019 0.4338282 -0.900995 -0.00115329 0.3477764 -0.9375769 -0.001163303 0.3549681 -0.9348778 0.001163303 0.1823353 -0.9832357 -0.001163482 0.1747764 -0.9846075 0.001163899 -0.00384134 -0.999992 -0.001163482 0.00384134 -0.999992 0.001163482 -0.1608297 -0.9869815 -0.001164853 -0.1823341 -0.9832294 0.003793418 -0.2833294 -0.9590141 -0.004073023 -0.345926 -0.9382432 0.005916833 -0.4176028 -0.908617 -0.004794418 -0.598401 -0.8011828 0.004751086 -0.6608176 -0.7505306 -0.004921555 -0.7149745 -0.6991457 0.002599179 -0.7804294 -0.6252375 -0.002855718 -0.7994427 -0.6007381 0.002281725 -0.5238961 -0.8517809 -0.001487851 -0.4952348 -0.868754 0.002985894 -0.5290505 -0.8485899 -9.25346e-4 -0.9349683 -0.3547294 -0.001169741 -0.8826787 -0.4699562 -0.004412591 -0.8701835 -0.4927257 0.001485228 -0.9238826 -0.3826532 0.004193961 -0.9534592 -0.3014503 -0.006585061 -0.9735596 -0.2283284 0.00693643 -0.991688 -0.1284713 -0.00708431 -0.9983266 -0.05770969 0.003684878 -0.9996348 0.02689003 -0.002722918 -0.9980207 0.06282842 0.002722859 -0.9883671 0.1520324 -0.004072904 -0.9787647 0.2049468 0.004072844 -0.952229 0.3053614 -0.003793478 -0.9453434 0.3260745 0.001164436 -0.8780559 0.4785581 -3.24278e-4 -0.8805357 0.4739783 0.001162648 -0.8260802 0.5635439 0.003146231 -0.8238105 0.5668634 0.001462042 -6.69624e-6 0 -1 4.55235e-6 0 -1 -3.34813e-6 0 -1 3.65847e-7 0 -1 3.34813e-6 0 -1 -4.55234e-6 0 -1 6.69623e-6 0 -1 1.64339e-7 0 -1 -2.12769e-7 0 -1 2.00404e-7 0 -1 -2.27617e-6 0 -1 -0.8854556 0.4647241 0 -0.9709419 0.2393155 0 -0.748511 0.6631224 0 -0.8854567 0.4647222 0 0.1205367 0.9927089 0 -0.5680637 0.8229847 0 -0.7485105 0.663123 0 0.3546041 0.9350166 0 0.1205372 0.9927088 0 -0.354604 0.9350166 0 -0.5680657 0.8229833 0 0.5680637 0.8229847 0 0.3546056 0.935016 0 -0.1205367 0.9927089 0 -0.3546057 0.9350159 0 0.7485105 0.663123 0 0.5680657 0.8229833 0 -0.1205372 0.9927088 0 0.8854557 0.4647237 0 0.748511 0.6631224 0 0.9709418 0.239316 0 0.8854564 0.4647225 0 0.970942 0.239315 0 0.9709419 -0.2393155 0 0.9709419 -0.2393155 0 0.8854557 -0.4647237 0 0.748511 -0.6631224 0 0.8854564 -0.4647225 0 0.5680637 -0.8229847 0 0.7485105 -0.663123 0 0.5680657 -0.8229833 0 0.354604 -0.9350166 0 0.3546057 -0.9350159 0 0.1205367 -0.9927089 0 0.1205372 -0.9927088 0 -0.1205367 -0.9927089 0 -0.1205372 -0.9927088 0 -0.3546041 -0.9350166 0 -0.3546056 -0.935016 0 -0.5680637 -0.8229847 0 -0.5680657 -0.8229833 0 -0.7485105 -0.663123 0 -0.748511 -0.6631224 0 -0.8854557 -0.4647237 0 -0.8854564 -0.4647225 0 -0.9709418 -0.239316 0 -0.970942 -0.239315 0 -0.9709419 0.2393155 0 -3.68188e-7 0 -1 -1.46662e-6 0 -1 -0.772467 -0.6342486 -0.03199255 -0.7116237 -0.7017809 0.03309541 -0.6323512 -0.7737799 -0.03737318 -0.5404995 -0.840514 0.0373733 -0.4497731 -0.8925884 -0.03146511 -0.3645242 -0.9307121 0.02995604 -0.2789641 -0.9599948 -0.02427136 -0.1356456 -0.9906614 -0.01380026 -0.1794294 -0.9836513 0.0153405 -0.03134632 -0.999296 0.02061665 0.03134626 -0.999296 -0.02061694 0.1794421 -0.9837229 -0.009474635 0.1497113 -0.9885572 0.01847165 0.3646812 -0.9311138 -0.005890905 0.3518347 -0.935993 0.01137763 0.5268959 -0.8499094 -0.005898296 0.5482887 -0.8360681 0.01922625 0.6393678 -0.7686895 -0.01803511 0.6918976 -0.7215875 0.02427303 0.7621527 -0.6472157 -0.01534056 0.7915338 -0.610933 0.01534003 0.8508863 -0.5247464 -0.02517765 0.8946475 -0.4454451 0.03441756 0.9354856 -0.3518412 -0.0327813 0.9622869 -0.2714385 0.01803535 0.9840915 -0.1771259 -0.01380008 0.9906612 -0.135647 0.01380014 0.9990683 -0.03920978 -0.01803535 0.9992139 0.03134453 0.02427297 0.9909544 0.1333199 -0.01534014 0.9840916 0.1771255 0.01380008 0.9600734 0.2789877 -0.02061718 0.9355688 0.3518718 0.02995616 0.8935825 0.4477005 -0.03278177 0.8508863 0.5247464 0.02517777 0.7827791 0.6219525 -0.02078175 0.7622091 0.6472616 0.009475111 0.6472616 0.7622092 -0.009475111 0.6219525 0.7827792 0.02078109 0.5247449 0.8508872 -0.0251767 0.4477002 0.8935828 0.03278154 0.370537 0.9286426 -0.01803553 0.238472 0.9711315 -0.005898475 0.2630934 0.9645789 0.01922535 0.05910331 0.9982345 -0.005890309 0.04537755 0.9989052 0.01137679 -0.1495443 0.9886897 -0.01137667 -0.1631241 0.986588 0.005889356 -0.3624777 0.9317942 -0.01922458 -0.3386768 0.9408843 0.005897164 -0.4655798 0.8848221 0.01803606 -0.5267497 0.8496739 -0.02427214 -0.6472147 0.7621534 -0.01534062 -0.610934 0.7915329 0.01534056 -0.7215886 0.6918965 0.02427238 -0.7686884 0.6393692 -0.01803588 -0.8499089 0.5268968 -0.005898296 -0.8360687 0.5482879 0.01922583 -0.9311142 0.3646804 -0.005890011 -0.9279698 0.3723012 -0.016245 -0.9709171 0.2384192 0.02182596 -0.983542 0.1794095 -0.02138602 -0.999491 0.03135091 -0.005897819 -0.9982007 0.05679774 0.0192247 -0.988362 -0.152007 -0.0058887 -0.9869605 -0.1608548 0.005888819 -0.938735 -0.3442571 0.01624453 -0.9359723 -0.3520244 0.005890071 -0.8799424 -0.4745492 -0.02245843 -0.8432161 -0.5365402 0.03333818 0 -1 1.19651e-5 0 -1 -9.63824e-6 0 -1 1.63769e-5 0 -1 -8.49203e-6 -0.06830835 -0.02827888 0.9972634 0.9943373 0.01369994 -0.1053842 0.2597553 0.0284987 0.965254 0.7822142 0.007418155 -0.6229654 0.4453446 -0.01285576 0.8952671 0.7356504 -0.01542025 -0.6771858 0.8399749 0.01742237 0.5423455 0.8136804 0.003961861 0.581299 0.254083 0.005554437 -0.9671666 0.2603434 0.003767967 -0.9655088 0.9993874 -0.02415657 0.02532607 -0.2603412 -0.003767967 -0.9655094 -0.2540793 -0.005554676 -0.9671675 -0.712652 0.01436191 -0.7013707 -0.782157 -0.0143612 -0.622916 -0.98985 0.003769755 -0.1420662 -0.9907416 0.005555391 -0.1356476 -0.9424856 -0.004769027 0.3342128 -0.9125075 0.01288986 0.4088569 -0.6515274 -0.01851236 0.7583993 -0.4746189 0.03036016 0.8796676 0 -1 5.39706e-6 0 -1 -3.12102e-6 0 -1 1.20269e-6 -0.06830811 -0.028279 0.9972635 0.9942601 0.01851421 -0.105376 0.2597545 0.02849829 0.9652541 0.7822028 0.009097516 -0.6229574 0.4453412 -0.01285457 0.8952687 0.834656 -0.01555228 -0.5505521 0.8136812 0.003962993 0.5812979 0.2540821 0.00555396 -0.9671667 0.3050918 -0.009097993 -0.9522795 0.9974636 -0.02101671 0.06800597 -0.2603419 -0.003767669 -0.9655092 -0.254077 -0.005554378 -0.9671681 -0.7126514 0.0143609 -0.7013714 -0.7821574 -0.0143612 -0.6229155 -0.98985 0.003769755 -0.1420664 -0.9907417 0.005553424 -0.1356475 -0.9424868 -0.004767894 0.3342093 -0.9125076 0.0128898 0.4088566 -0.6515254 -0.01851332 0.7584009 -0.474618 0.0303598 0.8796682 0 -1 3.12819e-5 -0.1392895 0.005184054 0.9902381 -0.06832742 -0.01436197 0.9975596 0.9288373 0.02639734 -0.3695462 0.4453825 0.003768622 0.8953325 0.5200543 0.02729976 0.8536968 0.6467024 0.004769504 -0.7627276 0.7355514 -0.02230316 -0.6771017 0.8134017 -0.02639758 0.5811032 0.9764331 0.0230236 0.2145888 0.2181682 -0.00376892 -0.975904 0.2244778 -0.005553901 -0.9744634 0.999414 -0.02302396 0.02532678 -0.2603224 0.01285606 -0.9654362 -0.4370551 -0.02651464 -0.8990439 -0.679098 0.01929926 -0.7337939 -0.9234868 -0.0182442 -0.3831964 -0.9570223 0.00909841 -0.2898721 -0.9570223 -0.00909841 0.2898715 -0.927233 0.0155515 0.3741621 -0.6515231 -0.01851248 0.7584028 -0.5444631 0.01199024 0.8386992 0 -1 3.00669e-6 -0.06830811 -0.02827906 0.9972635 0.9290655 0.01434165 -0.3696372 0.2153828 0.02070724 0.9763101 0.4453353 -0.01414704 0.8952521 0.8344948 -0.02500778 -0.5504481 0.6465875 0.01930004 -0.7625957 0.7058094 0.01778399 0.7081786 0.8136023 -0.01434028 0.5812449 0.9848909 0.01273435 0.1727073 0.1723911 0.009097456 -0.9849866 0.2690806 -0.01824265 -0.9629449 0.997603 -0.01273459 0.06801581 -0.4511694 -0.005053937 -0.8924241 -0.4371872 -0.01021897 -0.8993124 -0.8350571 0.01285481 -0.5500131 -0.923316 -0.02651286 -0.383125 -0.9949072 0.01929944 -0.09893089 -0.9569548 -0.01500397 0.2898488 -0.9125079 0.01289063 0.4088559 -0.651524 -0.01851344 0.7584022 -0.4746168 0.03036105 0.8796688 0 -0.707106 0.7071076 0 -0.7071084 0.7071052 -0.0731129 -0.9973229 0.001263201 -1.46341e-6 0 -1 -0.09143066 0.9958102 0.001605093 0 0.7071052 0.7071084 0 0.7071115 0.7071021 -1 -4.47883e-7 0 -1 -5.59278e-6 0 -1 -4.99508e-7 0 0 -0.7071045 0.7071092 0 -0.707106 0.7071076 0 0.7071036 0.7071099 0 0.7071068 0.7071068 0 0.7071036 -0.7071099 0 -0.707106 -0.7071076 0 -0.7071045 -0.7071092 0 0.7071131 0.7071005 0 -0.7071107 0.7071028 0 -0.7071124 -0.7071013 0 0.70711 -0.7071036 0.994028 -0.002635478 0.1090937 0.9995037 -1.73754e-4 0.03150182 0 0.9999899 0.004489064 -1.37058e-4 0.9999612 0.008813142 -0.9977876 7.81137e-4 0.06647765 -0.9983615 4.87439e-4 0.05721998 -2.23205e-4 -0.9998943 0.01454657 0 -0.999972 0.007486879 3.95664e-6 0 1 0 0 1 0 0 1 0 0 1 0 0 1 + + + + + + + + + + + + + + +

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

+
+
+
+ + + + 0.1098 -0.04492568 -0.08565253 0.1098 -0.08952987 -0.08618825 0.1098 -0.03399997 -0.09599995 0.1098 -0.09012538 -0.08671581 0.1098 -0.0434792 -0.08697384 0.1098 -0.09387457 -0.08671581 0.1098 -0.1 -0.09599995 0.1098 -0.09447008 -0.08618825 0.1098 -0.089078 -0.08553355 0.1098 -0.0887959 -0.08478969 0.1098 -0.094922 -0.08553355 0.1098 -0.09317016 -0.08708554 0.1098 -0.04149228 -0.08732157 0.1098 -0.09520411 -0.08478969 0.1098 -0.0452857 -0.08329683 0.1098 -0.08869999 -0.08399999 0.1098 -0.09239774 -0.08727592 0.1098 -0.09529995 -0.08399999 0.1098 -0.0916022 -0.08727592 0.1098 -0.0887959 -0.08321022 0.1098 -0.09082978 -0.08708554 0.1098 -0.089078 -0.08246642 0.1098 -0.03912389 -0.08584028 0.1098 -0.04399311 -0.08129477 0.1098 -0.08952987 -0.08181166 0.1098 -0.09012538 -0.08128416 0.1098 -0.1 -0.07199996 0.1098 -0.09520411 -0.08321022 0.1098 -0.094922 -0.08246642 0.1098 -0.09447008 -0.08181166 0.1098 -0.09387457 -0.08128416 0.1098 -0.09317016 -0.08091443 0.1098 -0.09239774 -0.08072406 0.1098 -0.0916022 -0.08072406 0.1098 -0.09082978 -0.08091443 0.1098 -0.03399997 -0.07199996 0.1098 -0.0412991 -0.08065819 0.1098 -0.03885161 -0.08267843 0.1708 -0.09352403 -0.08104676 0.1098 -0.0929324 -0.08071529 0.1708 -0.09197711 -0.08067679 0.1708 -0.08890086 -0.08519977 0.1708 -0.08872747 -0.08322811 0.1098 -0.08871424 -0.08470314 0.1708 -0.09006237 -0.08125215 0.1098 -0.09052073 -0.08102613 0.1708 -0.08981335 -0.08650255 0.1098 -0.08974397 -0.08643764 0.1098 -0.08907431 -0.08234745 0.1708 -0.09162807 -0.08734166 0.1098 -0.09149229 -0.08732157 0.1708 -0.09356456 -0.08693194 0.1098 -0.09417355 -0.08663326 0.1708 -0.0947479 -0.08586901 0.1098 -0.09535855 -0.08410358 0.1708 -0.09536212 -0.08396631 0.1098 -0.09477376 -0.08217293 0.1708 -0.09472191 -0.08209329 0.1708 -0.04237186 -0.08065831 0.1708 -0.04418659 -0.08149743 0.1708 -0.03890079 -0.08519977 0.1708 -0.03872746 -0.08322811 0.1708 -0.04006236 -0.08125215 0.1708 -0.0401178 -0.08678609 0.1708 -0.04243868 -0.08733355 0.1708 -0.04422086 -0.08647221 0.1708 -0.04511535 -0.08515697 0.1708 -0.04525637 -0.08316272 0.1340097 -0.08766961 -0.09599995 0.1403 -0.08849996 -0.09599995 0.1708 -0.1 -0.09599995 0.1098 -0.1 -0.09599995 0.1276625 -0.08439385 -0.09599995 0.1230618 -0.08002477 -0.09599995 0.1198523 -0.07364386 -0.09599995 0.1186982 -0.0674048 -0.09599995 0.1708 -0.03399997 -0.09599995 0.1403 -0.04549998 -0.09599995 0.1332397 -0.04658055 -0.09599995 0.1276625 -0.04960614 -0.09599995 0.1225859 -0.05463021 -0.09599995 0.1198523 -0.06035614 -0.09599995 0.1708 -0.1 -0.07199996 0.1098 -0.1 -0.07199996 0.1276625 -0.08439385 -0.07199996 0.1243224 -0.08138626 -0.07199996 0.1204011 -0.0754162 -0.07199996 0.1332397 -0.08741939 -0.07199996 0.1186982 -0.06659513 -0.07199996 0.1403 -0.08849996 -0.07199996 0.1230618 -0.05397522 -0.07199996 0.1198523 -0.06035614 -0.07199996 0.1276625 -0.04960614 -0.07199996 0.1340097 -0.04633039 -0.07199996 0.1708 -0.03399997 -0.07199996 0.1403 -0.04549998 -0.07199996 0.1465902 -0.04633039 -0.09599995 0.1529374 -0.04960614 -0.09599995 0.1575381 -0.05397516 -0.09599995 0.1607477 -0.06035614 -0.09599995 0.1619017 -0.06659513 -0.09599995 0.1473602 -0.08741939 -0.09599995 0.1529374 -0.08439385 -0.09599995 0.158014 -0.07936978 -0.09599995 0.1607477 -0.07364386 -0.09599995 0.1529374 -0.04960614 -0.07199996 0.1562775 -0.05261367 -0.07199996 0.1601989 -0.05858373 -0.07199996 0.1473602 -0.04658055 -0.07199996 0.1619017 -0.06740474 -0.07199996 0.1575381 -0.08002477 -0.07199996 0.1607477 -0.07364386 -0.07199996 0.1529374 -0.08439385 -0.07199996 0.1465902 -0.08766961 -0.07199996 0.1708 -0.089078 -0.08553355 0.1708 -0.08952987 -0.08618825 0.1708 -0.1 -0.09599995 0.1708 -0.09012538 -0.08671581 0.1708 -0.09082978 -0.08708554 0.1708 -0.0887959 -0.08478969 0.1708 -0.0916022 -0.08727592 0.1708 -0.08869999 -0.08399999 0.1708 -0.09239774 -0.08727592 0.1708 -0.0887959 -0.08321022 0.1708 -0.09317016 -0.08708554 0.1708 -0.089078 -0.08246642 0.1708 -0.09387457 -0.08671581 0.1708 -0.08952987 -0.08181166 0.1708 -0.09447008 -0.08618825 0.1708 -0.09012538 -0.08128416 0.1708 -0.094922 -0.08553355 0.1708 -0.09520411 -0.08478969 0.1708 -0.09529995 -0.08399999 0.1708 -0.1 -0.07199996 0.1708 -0.09082978 -0.08091443 0.1708 -0.0916022 -0.08072406 0.1708 -0.09239774 -0.08072406 0.1708 -0.09317016 -0.08091443 0.1708 -0.09387457 -0.08128416 0.1708 -0.09447008 -0.08181166 0.1708 -0.094922 -0.08246642 0.1708 -0.09520411 -0.08321022 + + + + + + + + + + -1 0 0 -1 0 0 -1 4.25256e-7 0 -1 2.84422e-5 0 -1 -1.41235e-7 0 -1 -2.2649e-5 0 -1 -3.67798e-6 0 -1 2.99047e-7 0 -1 5.98548e-6 0 -1 -1.5136e-5 0 -1 7.22663e-6 0 -1 -2.49181e-6 0 -1 -6.6111e-6 0 -1 1.22753e-5 0 -1 1.46657e-5 0 -1 -2.26495e-5 0 -1 0 0 -1 7.79058e-7 0 -1 -2.93841e-7 0 -1 -2.42959e-6 0 -1 2.43703e-7 0 -0.003029108 0.232612 -0.9725649 -0.002334058 -0.996154 0.08758902 -0.001385509 -0.2877765 -0.9576967 0.002628207 -0.1278473 -0.9917905 -3.21259e-4 -0.8190657 0.5736997 0.001525819 -0.8598854 0.5104849 0.002332925 -0.6744425 -0.7383238 -6.35248e-4 -0.4196823 0.9076709 -0.003370463 -0.8286326 -0.5597828 4.36667e-4 -0.4511983 0.8924237 0.003438889 -0.9885141 -0.1510896 0.002723097 0.206992 0.9783389 8.72974e-4 0.2486312 0.9685979 -0.003029167 0.6682512 0.7439296 0.003211617 0.905569 0.4241869 -6.35237e-4 0.9516433 0.3072046 7.08552e-4 0.9570589 -0.289893 -3.82105e-4 0.9462496 -0.3234375 0.002288579 0.6579357 -0.7530708 4.9631e-4 0.6206869 -0.7840585 -0.001683235 0.4196835 -0.907669 0.004042506 0.2299641 -0.9731907 0.002723038 -0.9961543 0.08757424 0.002800405 -0.9963088 0.08579659 -0.004380762 -0.2490168 -0.9684894 -0.00349009 -0.7934134 0.6086732 0.005397379 -0.6365731 -0.7711975 -0.003358006 -0.8286308 -0.5597856 0.004505872 -0.5302511 0.8478287 -0.003370702 -0.2295708 0.9732862 0.002868354 0.1723859 0.9850254 -0.002112925 0.4351502 0.9003553 0.002128422 0.6744431 0.7383238 -0.001997053 0.8268843 0.5623686 0.001846492 0.9885193 0.151084 -6.35156e-4 0.9975099 0.07052463 8.73691e-4 0.8413615 -0.5404723 7.88228e-4 0.8401054 -0.5424228 0 0 -1 -7.38825e-7 0 -1 1.55384e-6 0 -1 -3.92191e-6 0 -1 1.72242e-6 0 -1 -2.69466e-6 0 -1 -1.14954e-6 0 -1 -1.22141e-7 -1 0 -1.22141e-7 -1 0 0 0 1 0 0 1 -1.65032e-6 0 1 -1.71989e-6 0 1 -2.41348e-6 0 1 -7.82707e-7 0 1 -6.24999e-7 0 1 1.0834e-6 0 1 0 1 0 1.10824e-6 0 -1 -1.55384e-6 0 -1 1.56541e-6 0 -1 -5.09919e-7 0 -1 -6.88973e-7 0 -1 2.69463e-6 0 -1 -2.29906e-6 0 -1 0.1512885 -0.9884747 0.005450606 0.1308768 -0.9913987 0 0.4768441 -0.878988 0 0.4586123 -0.8886198 -0.005450785 0.7034093 -0.7107642 0.005450427 0.6886128 -0.7251293 0 0.9024302 -0.4308364 0 0.8933422 -0.449344 -0.005450427 0.9868465 -0.1615686 0.005450606 0.9833195 -0.1818864 0 0.98328 0.1818752 -0.009053528 0.9818522 0.18954 -0.006394267 0.8932823 0.4493153 0.01275449 0.835759 0.5489485 -0.01275414 0.6886137 0.7251285 0 0.6691184 0.7431228 0.007014572 0.4586122 0.8886199 0.005450427 0.4768437 0.8789882 0 0.1308771 0.9913987 0 0.151287 0.9884749 -0.005450546 1.71989e-6 0 1 7.82702e-7 0 1 -3.12496e-6 0 1 2.23499e-7 0 1 1 2.44221e-7 2.26035e-7 1 -2.57539e-7 3.47218e-7 1 -5.03712e-6 0 1 0 -1.56397e-6 1 -1.11306e-5 -8.66924e-7 1 4.46448e-7 1.2897e-7 1 0 0 1 -6.70928e-7 0 1 9.41349e-6 -1.39827e-6 1 -4.21415e-7 0 1 0 -2.23934e-7 1 -8.4631e-7 0 1 -2.84766e-5 -3.24796e-6 1 -3.92994e-7 -1.29746e-7 1 -7.74306e-7 2.12049e-7 1 0 -2.37307e-7 1 3.01816e-7 -3.68077e-7 1 -2.39248e-6 8.17577e-7 1 -3.49696e-6 1.37835e-6 1 4.10418e-6 0 1 0 3.1126e-6 1 0 1.56897e-6 1 -1.88586e-7 -3.46711e-7 1 -5.0371e-6 0 1 1.41558e-6 0 1 -8.88827e-7 0 1 1.65278e-6 0 1 9.96724e-6 0 1 -3.61332e-6 0 1 -8.64915e-6 0 1 -1.79564e-5 0 1 0 3.68619e-7 1 -1.00085e-6 -2.2919e-7 -0.1512871 0.9884749 0.005449891 -0.1308779 0.9913985 0 -0.4768435 0.8789883 0 -0.4586122 0.8886199 -0.005450427 -0.703405 0.7107685 0.005450308 -0.6886109 0.725131 0 -0.9024294 0.4308379 0 -0.8933433 0.4493418 -0.005450725 -0.9868462 0.1615704 0.005450427 -0.9833194 0.1818875 0 -0.9832798 -0.1818761 -0.009052693 -0.9818513 -0.1895447 -0.006394028 -0.8932827 -0.4493145 0.01275479 -0.835759 -0.5489485 -0.01275491 -0.6886117 -0.7251303 0 -0.6691158 -0.7431252 0.007012665 -0.4586129 -0.8886194 0.005450427 -0.4768437 -0.8789882 0 -0.1308779 -0.9913985 0 -0.1512881 -0.9884747 -0.005450546 + + + + + + + + + + + + + + +

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

+
+
+
+ + + + -0.02159696 5.48524e-4 -0.2802411 -0.01947468 -0.008232831 -0.2886541 -0.02091163 -0.008957862 -0.2837272 -0.01851284 0.002074539 -0.290011 -0.01689171 -0.007478415 -0.2930839 0.01851284 -0.002074539 -0.267989 0.01738142 -0.007977366 -0.2671205 0.01996433 -0.00722295 -0.2715504 -0.01331287 -0.006738543 -0.2967593 -0.01118701 0.00312525 -0.297258 -0.008946061 -0.006056189 -0.2994667 0.01380252 -0.008717238 -0.2634451 -0.004045128 -0.005470931 -0.3010486 0.01118731 -0.00312519 -0.2607422 0.009435713 -0.009399592 -0.2607378 -0.004326879 0.003421425 -0.2997803 3.61855e-4 0.003404915 -0.3003497 0.003875672 -0.003417313 -0.2582743 0.005625247 0.003220796 -0.2995454 -0.001235902 -0.003410041 -0.2579035 0.01231276 -0.01537716 -0.29962 -0.006268084 -0.003173232 -0.2587186 0.01072484 0.002798378 -0.2974227 0.01477897 0.002230703 -0.294332 -0.009008169 -0.02251082 -0.2629625 0.01809722 0.001497864 -0.2902609 0.02029627 6.85114e-4 -0.2855446 -0.01072484 -0.002798378 -0.2605773 -0.01498699 -0.00225228 -0.2635959 0.02160865 -0.005844414 -0.2816147 0.02159696 -5.48525e-4 -0.2777588 0.02140128 -0.006497919 -0.2764772 -0.01786911 -0.01055848 -0.2688718 -0.01973301 -0.001103043 -0.2701875 -0.02008479 -0.01015549 -0.2735401 -0.02111899 -0.009611427 -0.2785897 -0.01947402 -0.0192905 -0.2847409 -0.01971405 -0.01970946 -0.2795804 -0.01802581 -0.01864665 -0.2896757 -0.01545357 -0.01781535 -0.294098 -0.01190674 -0.01684486 -0.2977508 0.01864039 -0.01515954 -0.2679259 0.02115994 -0.01429504 -0.2723647 -0.00635147 -0.02032881 -0.3008844 0.01515233 -0.01624757 -0.2642462 -0.001621007 -0.01908206 -0.302307 0.01089185 -0.01750171 -0.261542 0.003316044 -0.01787346 -0.3025446 0.006102502 -0.018862 -0.2599784 0.009655773 -0.02225869 -0.3018147 0.001067698 -0.0202775 -0.2596597 -0.003901243 -0.0217117 -0.2606189 0.01653897 -0.01429307 -0.2962761 0.01968109 -0.01372444 -0.292232 0.02180564 -0.01341283 -0.2875369 -0.01273256 -0.02321326 -0.266052 0.02278792 -0.01340025 -0.2824628 0.02256894 -0.01369833 -0.2773057 -0.01586371 -0.02392524 -0.2702351 -0.01793181 -0.02430039 -0.2750661 -0.01710712 -0.02843165 -0.2851505 -0.01740801 -0.02861571 -0.2799795 -0.01563584 -0.02787703 -0.2900894 -0.01307952 -0.02698421 -0.2945089 -0.009586751 -0.02580493 -0.2981523 -0.01203346 -0.03710144 -0.2899181 -0.01355338 -0.03753167 -0.2849816 -0.009492993 -0.03616803 -0.2943384 0.02054733 -0.02071696 -0.2677331 0.02308779 -0.01978355 -0.2721534 -0.006079614 -0.03478562 -0.2979856 -0.001991689 -0.03303462 -0.3006477 0.01713395 -0.02209937 -0.2640859 0.002533197 -0.0310167 -0.3021701 0.01427555 -0.02687454 -0.2611318 0.007232069 -0.02884918 -0.3024642 0.009960055 -0.02928531 -0.2596436 0.005551159 -0.03194546 -0.2593611 0.00135529 -0.03475886 -0.2602794 0.02149379 -0.02624696 -0.2958466 0.02420461 -0.02443146 -0.2916477 0.02583146 -0.02300924 -0.2868409 -0.006307244 -0.03872835 -0.2654976 0.02635049 -0.02214175 -0.2817169 0.02577078 -0.02189284 -0.2765703 -0.01143002 -0.03570598 -0.2699929 -0.01324266 -0.03681302 -0.2747208 -0.01396441 -0.03743362 -0.2798158 -0.006934821 -0.04902571 -0.2836553 -0.007569611 -0.04853898 -0.2785343 -0.00530821 -0.04878079 -0.2885704 -0.002784311 -0.04781854 -0.292994 4.90063e-4 -0.04619479 -0.2966691 0.02304553 -0.02505546 -0.2672325 0.02556937 -0.02409321 -0.2716561 0.004324734 -0.04400396 -0.299382 0.01977109 -0.02667921 -0.2635574 0.00849688 -0.04137337 -0.300975 0.01276391 -0.03845596 -0.3013557 0.02038484 -0.03999501 -0.2995334 0.0274586 -0.04136228 -0.2964582 0.006232619 -0.04897964 -0.2598446 -0.005776166 -0.04552471 -0.2688599 -0.007175803 -0.04734891 -0.2735051 0.00119996 -0.05884617 -0.2810985 2.62262e-4 -0.05799376 -0.2760727 0.002993941 -0.05880331 -0.285961 0.005539834 -0.05786764 -0.2903777 0.008689761 -0.05609357 -0.2940919 0.0263254 -0.029015 -0.2662016 0.02887129 -0.02807933 -0.2706183 0.01226055 -0.05358421 -0.2968877 0.02317553 -0.03078901 -0.2624874 0.01604479 -0.05048543 -0.2986027 0.01960468 -0.03329843 -0.2596916 0.01982253 -0.04697722 -0.2991371 0.01582044 -0.03639721 -0.2579766 0.01500248 -0.04276359 -0.256384 0.01207363 -0.04709184 -0.2567982 0.03076052 -0.03802514 -0.2931176 0.03277868 -0.03513783 -0.289132 0.03163009 -0.03058701 -0.2854035 0.004864275 -0.05300343 -0.2622264 0.03160303 -0.02888888 -0.2805066 0.03066527 -0.02803647 -0.2754808 0.003892838 -0.05672061 -0.2656631 2.35218e-4 -0.05629563 -0.2711758 0.01326888 -0.06770908 -0.2817986 0.01125252 -0.06755912 -0.2770262 0.01587146 -0.06682252 -0.2861923 0.03083932 -0.03292739 -0.264373 0.0334419 -0.03204083 -0.2687668 0.01890897 -0.06495106 -0.289952 0.02220493 -0.0622034 -0.2928592 0.02780175 -0.0347988 -0.2606133 0.02556771 -0.0587393 -0.2947449 0.02450585 -0.03754645 -0.2577061 0.02880191 -0.05476003 -0.2954995 0.02114307 -0.04101055 -0.2558204 0.03171962 -0.05049681 -0.2950792 0.03970962 -0.03720724 -0.2818423 0.03909581 -0.03505516 -0.2770659 0.03545826 -0.03219074 -0.2735392 0.01267313 -0.06655639 -0.2657458 0.009939491 -0.06638145 -0.2721524 0.02131986 -0.07398015 -0.272158 0.0196501 -0.07257497 -0.2674567 0.02357488 -0.07428228 -0.276815 0.02628415 -0.07346373 -0.2811572 0.02929013 -0.07157224 -0.2849321 0.03649723 -0.03653603 -0.261637 0.0392065 -0.03571754 -0.2659792 0.03241825 -0.06871753 -0.2879204 0.03349119 -0.03842759 -0.2578621 0.03548663 -0.06506562 -0.2899485 0.03036314 -0.04128223 -0.2548738 0.03831696 -0.06082874 -0.2908984 0.02729475 -0.04493415 -0.2528457 0.04546678 -0.0585494 -0.2882679 0.02784669 -0.05072247 -0.2502298 0.04756814 -0.0541507 -0.2867859 0.02575266 -0.05555355 -0.2501534 0.04713237 -0.04898959 -0.2853701 0.02451026 -0.06064164 -0.2510712 0.04695522 -0.04471623 -0.2825415 0.02218157 -0.06467539 -0.2540585 0.04146152 -0.03601968 -0.2706362 0.02132856 -0.06859469 -0.2575926 0.03295153 -0.0787996 -0.2599256 0.03410637 -0.07934957 -0.2709596 0.03160613 -0.07892948 -0.2664389 0.03694385 -0.07859277 -0.2752304 0.04536843 -0.04068487 -0.2566363 0.04941564 -0.04038196 -0.2601588 0.0399537 -0.07670307 -0.2790033 0.042961 -0.07379031 -0.2820587 0.04299932 -0.04283225 -0.2524613 0.04579097 -0.07002371 -0.2842194 0.04013955 -0.04578757 -0.2493343 0.04827916 -0.06562221 -0.2853595 0.03751462 -0.04961639 -0.2470588 0.05402427 -0.04451316 -0.274246 0.05296456 -0.04201364 -0.2697598 0.05108958 -0.04050284 -0.2651489 0.03086066 -0.07589924 -0.2561388 0.04409092 -0.08300489 -0.2647058 0.04637819 -0.08411157 -0.257017 0.04707854 -0.08230304 -0.2688826 0.05014747 -0.08043497 -0.2726184 0.05311918 -0.0775091 -0.2756962 0.05582106 -0.07369565 -0.277937 0.05809605 -0.06921607 -0.2792107 0.05981194 -0.06433081 -0.2794432 0.0431953 -0.05659437 -0.2405202 0.06659525 -0.06109517 -0.2748115 0.04171133 -0.06155061 -0.2401204 0.06714189 -0.05631577 -0.2728208 0.04099535 -0.06666594 -0.2407011 0.06594091 -0.05168139 -0.2706176 0.04123562 -0.07167643 -0.2421259 0.04129534 -0.07595735 -0.245078 0.0606414 -0.08730357 -0.2532334 0.05885994 -0.08552891 -0.260581 0.0623629 -0.04539942 -0.244958 0.06618809 -0.04488956 -0.2484423 0.06202435 -0.08368694 -0.2642495 0.06499367 -0.08076047 -0.267329 0.05531132 -0.04636424 -0.2439776 0.06759536 -0.07691955 -0.2696404 0.05234199 -0.04929071 -0.2408981 0.06967818 -0.07238739 -0.2710495 0.04974031 -0.05313163 -0.2385867 0.07112115 -0.06742733 -0.2714743 0.07213604 -0.0497905 -0.261829 0.07070451 -0.04709279 -0.2576103 0.06465345 -0.04445093 -0.2558757 0.0505867 -0.08166486 -0.2426283 0.05369377 -0.08476144 -0.2457343 0.06871783 -0.08856827 -0.2393698 0.06987023 -0.08768409 -0.251831 0.07316827 -0.08586835 -0.2553933 0.07619845 -0.08295381 -0.2584244 0.0639503 -0.04805529 -0.2371121 0.0787847 -0.07910984 -0.2607481 0.06092005 -0.05096983 -0.234081 0.08077669 -0.07455986 -0.2622294 0.05833387 -0.0548138 -0.2317573 0.0820586 -0.06956833 -0.2627822 0.05634188 -0.05936378 -0.230276 0.082556 -0.06442534 -0.2623744 0.05505996 -0.06435531 -0.2297232 0.08955478 -0.06056356 -0.2547894 0.0545625 -0.0694983 -0.2301311 0.08876818 -0.05604612 -0.2522765 0.06132066 -0.07549244 -0.2259801 0.0788272 -0.04707092 -0.2443966 0.06309121 -0.08014327 -0.2275909 0.083916 -0.09043562 -0.2316148 0.08291852 -0.0893774 -0.2400014 0.08257085 -0.04817742 -0.2260916 0.08582156 -0.04749077 -0.2302935 0.08639842 -0.08758527 -0.2433988 0.08953309 -0.08468425 -0.2463352 0.07451707 -0.04942655 -0.2275323 0.09214025 -0.08084297 -0.2486399 0.0713824 -0.05232757 -0.2245959 0.09406858 -0.07628476 -0.250179 0.06877523 -0.05616879 -0.2222912 0.09520584 -0.07127445 -0.2508629 0.06684696 -0.060727 -0.2207521 0.09548598 -0.06610327 -0.2506521 0.06570971 -0.0657373 -0.2200682 0.0654295 -0.07090854 -0.220279 0.09952777 -0.05338442 -0.2369309 0.09625691 -0.05029708 -0.2340871 0.077398 -0.08520305 -0.2183005 0.080186 -0.08810657 -0.221392 0.09282273 -0.09034961 -0.2141764 0.09480845 -0.09022289 -0.2275051 0.0984953 -0.08844542 -0.2306849 0.1017795 -0.08555501 -0.2334642 0.08464103 -0.0501464 -0.216892 0.1044703 -0.08171975 -0.2356811 0.08135682 -0.0530368 -0.2141128 0.1064113 -0.07716244 -0.2372068 0.07866603 -0.05687206 -0.2118959 0.1074896 -0.0721479 -0.2379527 0.07672506 -0.06142944 -0.2103702 0.1076427 -0.06696766 -0.2378754 0.07564675 -0.06644392 -0.2096243 0.1068615 -0.06192272 -0.2369794 0.07549369 -0.07162415 -0.2097015 0.1051916 -0.05730628 -0.2353169 0.07627481 -0.07666909 -0.2105976 0.1016508 -0.048743 -0.2204987 0.07794481 -0.08128553 -0.2122601 0.1086984 -0.09106403 -0.2017282 0.1081539 -0.09050273 -0.2108184 0.1120955 -0.08873063 -0.2136798 0.1001632 -0.04861718 -0.2052734 0.104337 -0.04806214 -0.2082959 0.1155758 -0.08584439 -0.2162138 0.09622162 -0.05038928 -0.202412 0.1183926 -0.08201169 -0.2182731 0.09274131 -0.05327558 -0.199878 0.1203822 -0.0774554 -0.219738 0.08992451 -0.05710822 -0.1978186 0.1214289 -0.07244026 -0.2205235 0.08793491 -0.06166452 -0.1963537 0.1214719 -0.0672577 -0.2205837 0.08688819 -0.06667965 -0.1955683 0.1205088 -0.06220895 -0.2199154 0.08684515 -0.07186222 -0.1955081 0.1185954 -0.05758744 -0.2185572 0.1158429 -0.0536617 -0.2165881 0.08780837 -0.07691097 -0.1961765 0.1204584 -0.05048674 -0.202293 0.08972173 -0.08153247 -0.1975346 0.0924741 -0.08545821 -0.1995037 0.1033935 -0.08829891 -0.1909615 0.1172575 -0.08976709 -0.1762093 0.1195826 -0.09022432 -0.193175 0.1106521 -0.04836165 -0.1890808 0.1207199 -0.04753977 -0.1817626 0.1237799 -0.08844596 -0.1956416 0.1274737 -0.08555454 -0.1978459 0.1064548 -0.05013996 -0.1866142 0.1304495 -0.08171796 -0.1996599 0.102761 -0.05303144 -0.1844097 0.1325342 -0.07715934 -0.200978 0.0997852 -0.05686795 -0.1825959 0.1336067 -0.07214361 -0.2017236 0.09770047 -0.06142657 -0.1812778 0.1336046 -0.06696212 -0.2018533 0.09662801 -0.06644237 -0.1805322 0.1325282 -0.06191611 -0.20136 0.09663003 -0.0716238 -0.1804023 0.1304399 -0.05729883 -0.2002718 0.1274611 -0.05337864 -0.1986523 0.09770649 -0.07666981 -0.1808959 0.126399 -0.04814273 -0.1819576 0.0997948 -0.08128708 -0.181984 0.1027736 -0.08520734 -0.1836036 0.129415 -0.08981996 -0.1604154 0.1304142 -0.08955168 -0.1713943 0.1348699 -0.08775728 -0.1733412 0.1387854 -0.08485203 -0.1751 0.1162744 -0.0495302 -0.1668687 0.124415 -0.04742062 -0.1602756 0.141933 -0.08100485 -0.1765685 0.1123589 -0.05243539 -0.1651098 0.1441296 -0.07643932 -0.1776614 0.1092114 -0.05628263 -0.1636413 0.1452478 -0.07142066 -0.1783151 0.1070147 -0.06084817 -0.1625485 0.1452226 -0.06624066 -0.1784916 0.1058965 -0.06586682 -0.1618947 0.1440553 -0.06120032 -0.1781808 0.1059218 -0.07104682 -0.1617182 0.1418138 -0.05659258 -0.1774006 0.1386285 -0.05268514 -0.1761963 0.1070891 -0.07608717 -0.162029 0.1346843 -0.0497052 -0.1746383 0.1093305 -0.08069491 -0.1628091 0.1125159 -0.08460235 -0.1640134 0.11646 -0.08758229 -0.1655716 0.1312335 -0.08841258 -0.1358813 0.1414555 -0.08845001 -0.1374936 0.1361792 -0.04608231 -0.1381437 0.1430022 -0.08697688 -0.1500595 0.1471004 -0.08405411 -0.1512952 0.1236237 -0.0488249 -0.1458281 0.1503972 -0.08019256 -0.1523361 0.1195256 -0.05174767 -0.1445925 0.1527011 -0.07561671 -0.1531217 0.1162286 -0.05560916 -0.1435516 0.1538785 -0.0705924 -0.1536064 0.1139247 -0.06018507 -0.1427659 0.1538605 -0.06541168 -0.1537621 0.1127475 -0.06520932 -0.1422812 0.1526484 -0.06037563 -0.1535795 0.1127654 -0.07039004 -0.1421256 0.1503126 -0.05577695 -0.1530694 0.1469888 -0.05188286 -0.1522616 0.1139775 -0.0754261 -0.1423081 0.1428703 -0.04891961 -0.1512027 0.1412114 -0.04670512 -0.1391451 0.1163133 -0.08002483 -0.142818 0.1196371 -0.08391892 -0.143626 0.1237557 -0.08688211 -0.1446849 0.1537078 -0.05538284 -0.1390221 0.1202149 -0.05514669 -0.1261221 0.1236042 -0.0512728 -0.1267246 0.1560776 -0.05997765 -0.1393915 0.1584976 -0.05965679 -0.1249949 0.1516838 -0.05130338 -0.1317471 0.1561038 -0.05506521 -0.1247683 0.1178449 -0.05972796 -0.1256574 0.1474564 -0.04835891 -0.1311652 0.1166275 -0.06475049 -0.1253705 0.116631 -0.06992417 -0.1252835 0.1178539 -0.07495099 -0.1254072 0.120226 -0.07954108 -0.1257377 0.1236104 -0.0834285 -0.1262643 0.1278095 -0.0863865 -0.1269728 0.1395376 -0.08862191 -0.1178231 0.1476027 -0.08643651 -0.1298623 0.1517915 -0.08350789 -0.1307433 0.1551713 -0.0796386 -0.131462 0.1561108 -0.07522094 -0.1390148 0.1585169 -0.07490199 -0.1247008 0.157315 -0.07019352 -0.1393878 0.1597403 -0.06987202 -0.1249602 0.1341747 -0.04628276 -0.119321 0.1278223 -0.04833173 -0.1273959 0.1573038 -0.06501203 -0.1395158 0.1597337 -0.06468987 -0.1250602 0.1578608 -0.05486136 -0.1062011 0.1601755 -0.05946975 -0.1073655 0.1223577 -0.05492025 -0.1049197 0.1258109 -0.0509594 -0.1055334 0.1543442 -0.05097186 -0.1071798 0.1200411 -0.05944871 -0.1043238 0.1501582 -0.04800355 -0.1059686 0.1452236 -0.04616415 -0.1068416 0.1401419 -0.04552358 -0.1057089 0.1188009 -0.06438028 -0.1046659 0.118786 -0.06955718 -0.1046757 0.120009 -0.07459044 -0.1047471 0.1224007 -0.07918781 -0.1048818 0.1258245 -0.0830813 -0.105087 0.1300824 -0.0860424 -0.1053698 0.1349256 -0.0878964 -0.1057654 0.1462731 -0.08774632 -0.07200568 0.1501333 -0.08605813 -0.1054906 0.1543946 -0.08310431 -0.1059718 0.1578273 -0.0792095 -0.1062942 0.1602262 -0.07460337 -0.1065288 0.1614509 -0.06955677 -0.1066921 0.1301491 -0.04799365 -0.1046543 0.1614309 -0.06436574 -0.1067872 0.1611933 -0.07263362 -0.07199996 0.1579942 -0.07921338 -0.07199996 0.1616432 -0.06440842 -0.07199996 0.1330679 -0.04660469 -0.07199996 0.1433743 -0.04557991 -0.07199996 0.1596746 -0.05736178 -0.07199996 0.1260429 -0.05090701 -0.07199996 0.1529765 -0.04946213 -0.07199996 0.1226059 -0.05478656 -0.07199996 0.1193376 -0.06183326 -0.07199996 0.1189568 -0.06959152 -0.07199996 0.1209253 -0.07663786 -0.07199996 0.1276234 -0.0845378 -0.07199996 0.1372256 -0.08842003 -0.07199996 0.1522029 -0.0850718 -0.07199996 + + + + + + + + + + -0.960767 0.03177243 -0.2755312 -0.8648669 0.01464623 -0.5017877 -0.9546343 0.050448 -0.2934765 0.8669322 -0.0941599 0.4894511 -0.7227661 0.09742724 -0.6841909 -0.70687 0.1170783 -0.697587 -0.5336999 0.07242977 -0.8425666 0.7195953 -0.03590095 0.693465 -0.3196918 0.1471459 -0.9360263 0.537775 -0.1495447 0.8297195 0.7042063 -0.01377642 0.7098618 -0.1189466 0.136501 -0.983473 -0.3471574 0.1216283 -0.9298862 0.3217151 -0.08915138 0.9426301 0.6126142 0.147399 -0.7765163 0.3904187 0.1440404 -0.9092996 -0.5841516 -0.1474456 0.7981395 -0.3912213 -0.1440497 0.908953 0.9990001 -0.02485442 0.03716385 0.9831036 0.1091552 -0.1469439 0.9584019 0.02963125 0.2838801 0.9497228 0.05447989 0.3083157 -0.8155017 -0.08102029 0.5730556 -0.9008909 -0.1195284 0.4172632 -0.9798004 -0.03485566 0.1969169 -0.9836002 -0.0170868 0.1795516 -0.9973921 -0.05459499 -0.04720771 -0.9896076 -0.1321191 -0.05675607 -0.9506409 -0.1035711 -0.2924978 -0.9506428 -0.1035689 -0.2924923 -0.8566531 -0.06903153 -0.5112535 -0.8566527 -0.06903201 -0.5112542 -0.7130489 -0.0304889 -0.7004511 -0.7130407 -0.03049039 -0.7004594 0.8578918 0.09373009 0.5052093 0.8543256 0.08539342 0.5126751 -0.492798 -0.003154575 -0.8701381 -0.5280227 0.009844541 -0.8491733 0.7165774 0.05446684 0.6953779 0.7110562 0.04596376 0.7016313 -0.2963593 0.03545582 -0.9544182 -0.3110376 0.03778672 -0.9496462 0.5333587 0.01190286 0.8458054 0.5264822 0.003920614 0.8501772 -0.07048738 0.09266453 -0.9931993 -0.02024489 0.08846622 -0.9958735 0.3245275 -0.05738162 0.9441341 0.3846808 -0.02245563 0.9227765 0.1933056 0.1173358 -0.9740971 0.1541027 0.1225278 -0.9804281 0.08845037 -0.09119164 0.9918975 0.07184284 -0.09914523 0.9924761 0.3850927 0.1421316 -0.9118674 -0.1546034 -0.1202641 0.9806296 -0.1643409 -0.1243224 0.9785377 0.5879768 0.1560081 -0.7936906 -0.3941316 -0.1433806 0.9078008 0.7684273 0.1601808 -0.6195657 0.7792701 0.1544606 -0.6073551 0.8961963 0.1547112 -0.4158087 0.9060263 0.145722 -0.397343 -0.6129025 -0.1566656 0.7744717 0.9670642 0.1719924 -0.1876317 0.9845753 0.1229956 -0.1244332 0.9867374 0.1541671 0.05081135 0.9873213 0.1475147 0.05862003 -0.772989 -0.1780741 0.6089152 0.9496335 0.1275852 0.2862138 -0.7424262 -0.1561834 0.6514677 0.9481944 0.119912 0.2941914 -0.8950989 -0.1760666 0.4096323 -0.8991753 -0.1798965 0.3989001 -0.9692881 -0.1670076 0.1805245 -0.9626051 -0.1556835 0.221707 -0.9896081 -0.1321168 -0.05675441 -0.9667293 -0.2473928 -0.06504976 -0.9262608 -0.2263293 -0.3013572 -0.9262611 -0.2263275 -0.3013572 -0.8321704 -0.1921573 -0.5201615 -0.8321726 -0.1921566 -0.5201585 -0.6898717 -0.1468605 -0.7088788 -0.6898791 -0.1468575 -0.7088721 -0.5362035 -0.1012887 -0.8379896 -0.9596765 -0.2538895 0.1206696 -0.9667283 -0.2473961 -0.06505155 -0.8856819 -0.3515111 -0.3033275 -0.928974 -0.3640298 -0.06700575 -0.7911772 -0.318669 -0.5220046 -0.8856829 -0.3515138 -0.3033218 0.7981586 0.3004618 0.5221741 -0.6508988 -0.267384 -0.7105185 -0.7911723 -0.3186687 -0.522012 -0.6508977 -0.2673792 -0.7105214 -0.47284 -0.2005773 -0.858016 0.6577256 0.2503334 0.7104437 0.8054471 0.29422 0.5144801 -0.2720293 -0.1111493 -0.9558483 -0.450594 -0.1709401 -0.8762105 0.5227783 0.1997436 0.8287373 0.6664354 0.2449712 0.7041683 -0.04928964 -0.02860736 -0.9983748 -0.2616986 -0.1021019 -0.9597339 0.2553172 0.134075 0.9575161 0.4790551 0.2102397 0.8522357 0.144443 0.0442934 -0.9885213 -0.04257208 -0.02250367 -0.9988399 0.03644841 0.045569 0.998296 0.2735895 0.1318644 0.9527648 -0.1842494 -0.04567247 0.9818179 0.05053341 0.04494857 0.9977104 -0.3955844 -0.1357347 0.9083442 -0.1766542 -0.04558163 0.983217 0.743671 0.2865477 -0.6040231 0.5732221 0.2091295 -0.7922634 0.8555811 0.3401728 -0.3902096 0.738988 0.2787355 -0.6133542 0.9148729 0.3724982 -0.1557328 0.8522943 0.3279989 -0.4074446 0.9201251 0.3822549 0.08515292 0.9164338 0.3582735 -0.1782956 -0.7207616 -0.2757695 0.6359669 0.8622184 0.3681197 0.3479476 -0.5978839 -0.2200655 0.7707828 0.9278506 0.3679846 0.06067007 0.8977521 0.3267135 0.2954649 -0.7484686 -0.2692246 0.6060634 -0.8591797 -0.3150647 0.403168 -0.8640973 -0.3129445 0.39421 -0.9239248 -0.3414889 0.172477 -0.9116353 -0.3520843 0.2120323 -0.9289737 -0.3640306 -0.06700474 -0.862124 -0.5032455 -0.05904412 -0.8131912 -0.5021981 -0.2941383 -0.8131876 -0.5022017 -0.2941419 -0.7174717 -0.4722358 -0.5120819 -0.7174817 -0.4722303 -0.5120729 -0.5804558 -0.4150779 -0.700558 -0.5804473 -0.4150792 -0.7005642 0.7174779 0.4722281 0.5120803 0.717485 0.4722294 0.5120691 -0.4097811 -0.3339087 -0.8488725 -0.4097673 -0.3339095 -0.8488788 0.5804518 0.4150815 0.7005592 0.5804502 0.4150722 0.700566 -0.2150289 -0.2332515 -0.9483441 -0.215049 -0.2332531 -0.9483391 0.3737188 0.3158257 0.8721173 -0.0073421 -0.1188026 -0.9928908 -0.007349073 -0.1188009 -0.992891 0.235907 0.01773285 -0.9716139 0.221086 0.01478791 -0.9751423 0.4167023 0.1334704 -0.8991912 0.408062 0.1306173 -0.9035622 0.6270934 0.27692 -0.7280586 -0.3493407 -0.0913071 0.9325365 -0.5432024 -0.2172465 0.8110088 -0.7259621 -0.3496943 0.5921934 0.8236496 0.5042307 0.2595241 -0.8104349 -0.419487 0.4089329 -0.8104395 -0.4194858 0.4089252 -0.8612931 -0.4751986 0.1798901 -0.8612934 -0.4751969 0.1798933 -0.8621229 -0.5032475 -0.05904412 -0.7653223 -0.6427601 -0.03378546 -0.7069896 -0.6550462 -0.2666087 -0.7069884 -0.6550482 -0.2666072 -0.607946 -0.6295518 -0.4838039 -0.6079401 -0.6295537 -0.483809 -0.4738903 -0.5677868 -0.673087 -0.4738907 -0.5677881 -0.6730858 0.6079419 0.6295579 0.4838013 0.6079382 0.6295557 0.4838087 -0.3123732 -0.4732153 -0.8237053 -0.3123846 -0.4732161 -0.8237004 0.4738834 0.5677857 0.6730929 0.4738809 0.5677978 0.6730844 -0.132539 -0.3511155 -0.9269042 -0.1325394 -0.3511103 -0.9269061 0.3268916 0.4566804 0.8273965 0.3376161 0.4890453 0.80427 0.05537956 -0.208369 -0.9764812 0.05533957 -0.2083753 -0.9764822 0.1450866 0.3375501 0.930059 0.1402968 0.325993 0.934904 0.2180153 -0.07279741 -0.9732266 -0.02421122 0.2455412 0.9690838 -0.05067867 0.188138 0.9808343 -0.2369732 0.06761252 0.9691607 -0.246192 0.05126696 0.9678643 0.5520549 0.2500305 -0.7954371 -0.4284688 -0.1195749 0.8956095 0.6739546 0.3927009 -0.6257566 0.6838626 0.3960644 -0.612752 0.7657013 0.5121089 -0.3891608 0.7571687 0.5106525 -0.4073445 -0.5689095 -0.2669672 0.7778628 0.7904503 0.5800553 -0.196785 0.797464 0.5764011 -0.1783619 0.7781683 0.6268514 0.03887909 0.7826592 0.6197254 0.05818212 -0.6708401 -0.4012791 0.6236576 0.7069906 0.6550465 0.2666053 -0.6651619 -0.3722134 0.6473152 0.7162528 0.6254934 0.3094189 -0.7411437 -0.5182035 0.4268153 -0.7408301 -0.4956476 0.4533259 -0.7794443 -0.5932128 0.2014081 -0.7794443 -0.5932129 0.2014083 -0.7653266 -0.6427549 -0.03378427 -0.5853781 -0.7795349 -0.2228409 -0.6562326 -0.7545385 0.00552988 -0.4808405 -0.7595251 -0.43808 -0.5853868 -0.7795283 -0.2228408 0.4808541 0.7595217 0.4380711 -0.3486347 -0.6957563 -0.6279944 -0.4808496 -0.7595233 -0.4380732 -0.3486338 -0.6957579 -0.6279931 -0.196242 -0.5918212 -0.7818163 0.3486357 0.6957554 0.627995 0.4808486 0.7595236 0.4380737 -0.03227013 -0.4535141 -0.8906647 -0.1962315 -0.5918178 -0.7818216 0.1962432 0.5918201 0.7818169 0.3486303 0.6957563 0.6279971 0.1339102 -0.2886106 -0.9480358 -0.0322712 -0.4535175 -0.890663 0.03227007 0.4535152 0.8906641 0.1962342 0.5918202 0.781819 0.2925994 -0.1065636 -0.9502789 0.1339079 -0.2886039 -0.9480383 -0.1613305 0.2589639 0.9523183 0.03226184 0.4535158 0.8906642 0.4065851 0.05195897 -0.9121342 0.3010326 -0.07818788 -0.9504031 0.6753612 0.7010096 -0.2290695 0.6728469 0.5630087 -0.4798941 0.6300297 0.7763313 0.01929485 0.6799048 0.6939789 -0.2369029 0.5853781 0.7795343 0.2228424 0.6562339 0.7545373 -0.005530357 0.5853855 0.7795293 0.2228406 -0.6805691 -0.6109381 0.4044508 -0.6802253 -0.6808038 0.2716611 -0.6891807 -0.6857644 0.2340025 -0.6562308 -0.7545402 0.005531489 -0.5545442 -0.8305718 0.05129539 -0.4696161 -0.8661112 -0.1712077 -0.4696176 -0.8661103 -0.1712082 -0.3575734 -0.851464 -0.3836017 -0.3575688 -0.851462 -0.3836107 -0.2248924 -0.7875698 -0.5737223 -0.2248842 -0.7875731 -0.5737211 0.3575723 0.8514648 0.3836011 0.3575685 0.8514668 0.3836002 -0.07916748 -0.6781165 -0.7306781 -0.0791881 -0.6781196 -0.730673 0.2248843 0.7875733 0.5737208 0.2248926 0.7875726 0.5737184 0.07120412 -0.5293353 -0.8454196 0.07119959 -0.5293325 -0.8454217 0.0791825 0.6781113 0.7306813 0.07918709 0.6781209 0.7306721 0.2176287 -0.3496761 -0.9112433 0.2176147 -0.3496749 -0.9112471 -0.07120168 0.5293341 0.8454205 -0.07119762 0.5293265 0.8454256 0.3784264 -0.1292446 -0.9165639 0.3515378 -0.1494825 -0.9241624 -0.190705 0.3891053 0.9012374 -0.1923368 0.3833269 0.9033643 0.4692885 0.07231271 -0.8800792 0.4864079 0.09579122 -0.868465 -0.3465924 0.164843 0.9234178 -0.3507559 0.1488682 0.9245586 0.5512066 0.2636943 -0.7916039 0.5466786 0.2568718 -0.7969689 -0.4572291 -0.04853737 0.8880235 -0.4535564 -0.03385162 0.8905845 0.6093389 0.4550673 -0.6493226 0.6122989 0.4598218 -0.6431594 0.6339568 0.6506441 -0.4180444 -0.5521573 -0.2663447 0.7900524 -0.5535839 -0.2766892 0.7854859 0.5645604 0.8210493 -0.08455508 -0.6097223 -0.4534766 0.6500752 0.4696131 0.8661121 0.1712117 -0.6097392 -0.4462592 0.655035 0.4696204 0.8661084 0.1712106 -0.6312554 -0.5679567 0.5281494 -0.6010259 -0.7637138 0.2356038 -0.5545504 -0.8305678 0.05129587 -0.4664356 -0.8792068 0.09712457 -0.3745745 -0.9191688 -0.1217486 -0.3745796 -0.9191672 -0.1217453 -0.2540532 -0.9091905 -0.3298935 -0.2540454 -0.9091928 -0.3298933 0.2252479 0.9140172 0.3373959 -0.118862 -0.8465673 -0.5188407 -0.1188569 -0.8465635 -0.5188481 0.2443081 0.9137304 0.3246697 0.02321869 -0.7349156 -0.677761 0.0232135 -0.7349168 -0.67776 0.1108593 0.8567982 0.5035942 0.1088204 0.8513195 0.5132379 0.1639806 -0.5806675 -0.7974558 0.1639887 -0.5806615 -0.7974585 -0.03653955 0.7427491 0.6685721 -0.03691411 0.7416107 0.6698142 0.295374 -0.3925821 -0.8709957 0.2953628 -0.3925896 -0.8709962 -0.1763501 0.5894097 0.7883508 -0.1768946 0.5872676 0.7898261 0.3958974 -0.2101622 -0.8939224 -0.3276283 0.3629723 0.8723021 0.5906922 0.6182514 -0.5185056 0.5501928 0.7779409 -0.3034732 0.5508836 0.7851445 -0.2829759 0.4657506 0.8793906 -0.09873586 0.4640449 0.8849971 -0.03797984 0.365636 0.9253457 0.1002289 0.3640155 0.9241021 0.116311 -0.5848539 -0.6731233 0.4526047 -0.5653903 -0.7518523 0.3391931 -0.5394505 -0.7853556 0.3036604 -0.4826799 -0.8679453 0.1170087 -0.304143 -0.951492 -0.04647624 -0.3843511 -0.9180029 0.09769839 -0.1701712 -0.9446626 -0.2804541 -0.2996602 -0.9509039 -0.07736772 -0.03085511 -0.8836131 -0.4672003 -0.1701765 -0.9446607 -0.2804571 -0.0308578 -0.8836182 -0.4671902 0.1102313 -0.7713307 -0.626816 0.24493 -0.6142946 -0.7501011 0.1102346 -0.7713201 -0.6268284 0.3654694 -0.4215719 -0.8298851 0.2449249 -0.6143138 -0.7500869 0.4648287 -0.2042722 -0.8615145 0.3654701 -0.4215614 -0.8298901 0.541581 0.0644263 -0.8381762 0.4648191 -0.1722937 -0.8684803 -0.4646295 0.2085559 0.8605951 -0.3214126 0.4948555 0.8073487 0.5800656 0.2557854 -0.7733679 0.5392287 0.02598714 -0.8417584 -0.537625 -0.02044624 0.8429362 -0.4611935 0.2135334 0.8612225 0.5862057 0.4667276 -0.6622147 0.5796501 0.2607255 -0.7720286 0.5541474 0.673845 -0.4887266 0.5869423 0.4636636 -0.6637129 -0.5792081 -0.2485447 0.7763656 -0.5377678 -0.02072018 0.8428384 -0.5862632 -0.4654344 0.6630734 -0.5774952 -0.2436662 0.779183 -0.5867539 -0.4681078 0.6607533 -0.5652629 -0.632165 0.5299484 -0.1968811 -0.9769877 -0.0820533 -0.1213598 -0.9711777 -0.2051483 -0.09279882 -0.9689478 -0.2291914 0.09106016 0.9661576 0.2413454 0.04516732 -0.9078442 -0.416868 0.04516476 -0.9078445 -0.4168677 0.1181601 0.9685329 0.2190487 0.1875985 -0.79597 -0.5755333 0.1875966 -0.7959696 -0.5755344 -0.05837845 0.8887186 0.454721 -0.04918783 0.8992704 0.4346185 0.3191654 -0.6379354 -0.7008367 0.3191608 -0.6379383 -0.7008361 -0.175946 0.7927039 0.583664 -0.1767784 0.7909154 0.5858348 0.4322407 -0.4428707 -0.7855148 0.432241 -0.4428684 -0.785516 -0.3082507 0.6350433 0.7083089 -0.3087462 0.6333693 0.7095908 0.520287 -0.2219894 -0.8246345 0.5202828 -0.2219957 -0.8246357 -0.4452141 0.3919515 0.8050829 0.5714665 -0.02385294 -0.8202788 0.5501138 0.6476961 -0.5271286 0.4737247 0.8060815 -0.3547078 0.4712136 0.8131271 -0.341734 0.3627405 0.9215825 -0.1382215 0.3666714 0.9179078 -0.1516492 0.2569451 0.9664179 0.003980696 0.2423541 0.9684627 0.05783188 -0.5438964 -0.6666899 0.509609 -0.4770473 -0.8048505 0.353046 -0.4686067 -0.8141424 0.3428993 -0.3983391 -0.8936206 0.206805 -0.2295311 -0.9722596 0.04502111 -0.2981315 -0.9443629 0.1389117 0.1113511 -0.9233165 -0.3675426 -0.004568219 -0.9722891 -0.2337372 0.1113517 -0.9233176 -0.3675397 0.2572433 -0.812117 -0.5237289 0.3881865 -0.6538008 -0.6495043 0.2572441 -0.8121196 -0.5237245 -0.2572453 0.8121184 0.5237257 -0.08196842 0.938863 0.3343913 0.4966056 -0.4575484 -0.7375855 0.3881886 -0.6538006 -0.6495032 -0.3881902 0.6538016 0.6495013 -0.2572376 0.8121212 0.5237252 0.5762225 -0.2346829 -0.7828741 0.4966032 -0.4575489 -0.7375868 -0.4966061 0.4575448 0.7375874 -0.3881891 0.6538028 0.6495007 0.6223883 0.001868009 -0.7827065 0.5762229 -0.2346863 -0.7828726 -0.5667101 0.2330642 0.7902663 -0.4729876 0.4822664 0.7373615 0.6251462 0.2901666 -0.7245659 0.6180043 0.02763432 -0.785689 -0.6148895 -0.003075778 0.7886074 -0.5665227 0.2333943 0.7903034 0.6068946 0.4644494 -0.644954 0.6359851 0.2336118 -0.735492 0.5469805 0.6514731 -0.5257331 0.607058 0.4640046 -0.6451205 -0.6277052 -0.1838859 0.7564206 -0.6150267 -0.003433763 0.7884989 -0.6085224 -0.4564674 0.6491056 0.1623414 0.9864257 0.0246911 -0.6355451 -0.2392194 0.7340685 0.339873 0.9166231 -0.2104485 -0.6085331 -0.4562236 0.6492669 -0.5426909 -0.6610516 0.5181673 -0.0193724 -0.9922307 -0.1228939 -0.1079258 -0.9937708 -0.02777898 -0.01069974 0.9881371 0.1532012 0.1684964 -0.9325402 -0.3193397 -0.02323693 -0.9929189 -0.1165001 0.1684961 -0.9325408 -0.3193381 0.3200222 -0.8222182 -0.4706834 -0.2048318 0.9126256 0.3537773 4.17658e-4 0.9893967 0.1452383 0.4529392 -0.6642293 -0.5946811 0.3200202 -0.8222209 -0.4706803 -0.3200187 0.822219 0.4706847 -0.1985549 0.9154447 0.3500528 0.559579 -0.4677325 -0.6841768 0.4529422 -0.6642274 -0.5946809 -0.4529365 0.6642296 0.5946828 -0.3200191 0.8222192 0.4706839 0.6337787 -0.2440497 -0.7340057 0.5595762 -0.4677315 -0.6841797 -0.5595763 0.4677326 0.6841788 -0.4529382 0.6642289 0.5946823 0.6712115 -0.006148874 -0.7412404 0.6337799 -0.2440521 -0.7340039 -0.6337796 0.2440485 0.7340053 -0.5595799 0.4677267 0.6841799 0.6730757 0.1860618 -0.7157864 0.6712107 -0.006141185 -0.7412412 -0.6712109 0.006133913 0.7412411 -0.6337753 0.2440573 0.7340061 -0.6658598 -0.2687532 0.6959903 -0.6712134 0.006126821 0.741239 0.4451594 0.8144403 -0.3721832 0.5406758 0.6788377 -0.4968392 0.2764853 0.9455861 -0.171531 0.4438293 0.8157032 -0.371004 0.1898846 0.979652 -0.06500691 -0.5687275 -0.6238505 0.5360595 -0.4424674 -0.8174658 0.3687444 -0.443334 -0.8162844 0.3703171 -0.3309802 -0.9140085 0.2346072 -0.1665166 -0.9819325 0.08989346 -0.2832033 -0.9369555 0.20472 0.2182071 -0.9375069 -0.2710471 0.06949943 -0.988674 -0.133018 0.2182059 -0.9375078 -0.2710449 0.3773536 -0.8278512 -0.4150505 0.5145289 -0.6701792 -0.5349017 0.3773516 -0.8278511 -0.4150522 -0.3773479 0.8278548 0.4150484 -0.1914356 0.9500677 0.2464219 0.6218245 -0.4736415 -0.6236972 0.5145325 -0.6701737 -0.5349053 -0.5145294 0.6701763 0.534905 -0.3773519 0.8278533 0.4150478 0.6930397 -0.2496235 -0.6763019 0.6218228 -0.4736453 -0.6236959 -0.6218281 0.4736397 0.6236948 -0.5145339 0.6701731 0.5349046 0.7240438 -0.01111 -0.6896646 0.6930398 -0.2496287 -0.6762998 -0.6930418 0.2496293 0.6762976 -0.6218228 0.4736441 0.6236967 0.7130171 0.2281624 -0.6629846 0.7240478 -0.01111173 -0.6896604 -0.724049 0.011101 0.6896593 -0.6930428 0.2496258 0.6762977 0.6559552 0.4543394 -0.6027426 0.7027981 0.2570672 -0.6633184 0.5819855 0.6277446 -0.5169426 0.6578923 0.4503408 -0.6036316 -0.7130228 -0.2281513 0.6629824 -0.7240474 0.01109999 0.6896609 -0.6558597 -0.4543486 0.6028395 0.0872156 0.9960967 -0.01359969 -0.7098392 -0.2026913 0.6745699 0.3054465 0.9247529 -0.2270122 -0.6553821 -0.4576113 0.600888 -0.5549376 -0.674129 0.4874365 -0.08116114 -0.9956218 0.04636842 0.06054258 -0.9960388 -0.06512618 0.03988111 -0.9977416 -0.05404835 0.2599644 -0.9393573 -0.2236656 0.2599653 -0.9393566 -0.2236682 -0.07256436 0.9939609 0.08231687 -0.08438259 0.9917219 0.096785 0.428642 -0.8300632 -0.3567368 0.4286457 -0.8300608 -0.356738 -0.2599636 0.9393578 0.2236652 -0.2867271 0.9215572 0.261763 0.5723384 -0.6726442 -0.4690188 0.572333 -0.6726508 -0.4690159 -0.4286434 0.8300635 0.3567344 -0.4286406 0.8300653 0.3567339 0.6827778 -0.4762821 -0.5540487 0.6827754 -0.4762837 -0.5540502 -0.5723368 0.6726468 0.469017 -0.5723373 0.6726452 0.4690186 0.753614 -0.2523454 -0.6069496 0.7536184 -0.2523382 -0.6069471 -0.6827768 0.4762791 0.5540524 -0.6827784 0.4762806 0.5540493 0.7807754 -0.01373273 -0.624661 0.7807708 -0.01376032 -0.624666 -0.7536144 0.2523541 0.6069454 -0.7536162 0.2523392 0.6069495 0.7626436 0.2257205 -0.6061561 0.7626445 0.2257471 -0.606145 -0.780771 0.01373708 0.6246663 -0.7807734 0.01374793 0.624663 0.7002167 0.4522493 -0.5524194 0.7002188 0.4522314 -0.5524314 0.5954381 0.6525437 -0.468658 0.5902308 0.662702 -0.460927 -0.7626423 -0.2257398 0.6061504 -0.7626429 -0.2257428 0.6061486 0.4361934 0.838324 -0.3270298 0.4584084 0.8140827 -0.3565548 0.3054999 0.924731 -0.2270302 -0.70022 -0.4522376 0.5524249 0.1299697 0.987976 -0.08373278 -0.7002184 -0.4522412 0.552424 -0.6032691 -0.6430989 0.4716887 -0.5954118 -0.6525432 0.468692 -0.4562943 -0.8159933 0.3548952 -0.4959867 -0.7839915 0.3733022 -0.2875927 -0.9336689 0.2134311 -0.1139267 -0.9895395 0.08850127 -0.3510021 -0.9051526 0.2397843 -0.1210575 0.9911077 0.05523294 0.2945541 -0.9392924 -0.175977 0.1304345 -0.9890612 -0.06888312 0.2945532 -0.9392927 -0.1759765 0.4741518 -0.8298917 -0.2940406 -0.2945497 0.9392941 0.1759745 -0.0977143 0.9940752 0.04760837 0.6260811 -0.6723432 -0.3949396 0.4741513 -0.8298929 -0.2940381 -0.4741546 0.8298903 0.2940403 -0.2945537 0.9392925 0.1759763 0.7415897 -0.475861 -0.4728648 0.6260814 -0.6723438 -0.3949379 -0.6260813 0.6723421 0.3949412 -0.4741472 0.8298953 0.2940378 0.8140532 -0.2518624 -0.5233383 0.7415907 -0.4758604 -0.4728638 -0.7415912 0.4758619 0.4728618 -0.6260806 0.6723437 0.3949394 0.8393237 -0.01327198 -0.54347 0.8140532 -0.2518662 -0.5233362 -0.8140558 0.25186 0.5233355 -0.7415935 0.4758567 0.4728631 0.8159402 0.2260836 -0.5320976 0.8393233 -0.01327645 -0.5434705 -0.8393218 0.0132867 0.5434726 -0.8140518 0.25187 0.5233368 0.7451906 0.452485 -0.4898453 0.8159406 0.226079 -0.5320991 0.6311222 0.6527075 -0.4191155 0.745194 0.4524794 -0.4898453 -0.8159344 -0.2260994 0.5320999 -0.8393241 0.01327747 0.5434692 0.5043075 0.794113 -0.3392026 0.6311189 0.6527113 -0.4191146 -0.7451963 -0.4524735 0.4898471 0.1024702 0.9914131 -0.08124005 -0.8159354 -0.226104 0.5320963 0.2690837 0.9446897 -0.1874981 0.09024024 0.9930716 -0.07527047 -0.7451959 -0.4524717 0.4898495 -0.6311188 -0.6527118 0.419114 -0.6311216 -0.6527082 0.4191152 -0.4595952 -0.8319566 0.3108385 0.09167104 -0.9956611 -0.01598638 -0.1232336 -0.9881455 0.09155327 0.3207585 -0.938122 -0.1305421 0.08647119 -0.9961792 -0.01223778 0.3207576 -0.9381219 -0.1305451 0.5116629 -0.8281403 -0.2288771 -0.3514819 0.926015 0.1376833 -0.08833944 0.9960435 0.009668529 0.6726534 -0.670116 -0.3138184 0.5116659 -0.8281383 -0.2288779 -0.5116522 0.828148 0.2288736 -0.3207546 0.9381232 0.1305432 0.7944738 -0.4733359 -0.3804796 0.6726492 -0.6701201 -0.3138186 -0.6726608 0.6701081 0.3138195 -0.5116688 0.8281365 0.2288779 0.8701804 -0.2492365 -0.42505 0.7944758 -0.473333 -0.3804789 -0.794478 0.4733295 0.3804785 -0.6726551 0.6701142 0.3138186 0.8954721 -0.01081043 -0.4449865 0.8701813 -0.2492421 -0.4250447 -0.8701784 0.2492486 0.4250468 -0.7944751 0.4733341 0.380479 0.8689106 0.2283136 -0.4391669 0.8954699 -0.01078075 -0.4449915 -0.8954712 0.01079654 0.4449886 -0.8701789 0.2492476 0.4250466 0.7919736 0.4543246 -0.4078814 0.8689156 0.2282952 -0.4391664 0.6690108 0.6541295 -0.3529011 0.7919732 0.4543251 -0.4078814 -0.8689115 -0.2283149 0.4391644 -0.8954708 0.01079839 0.4449895 0.5070157 0.816098 -0.2773434 0.6690068 0.6541345 -0.3528993 0.3564466 0.9106188 -0.2090919 0.4850279 0.8308005 -0.2729808 -0.7919778 -0.4543144 0.4078845 -0.8689122 -0.2283117 0.4391645 -0.7919765 -0.4543176 0.4078834 -0.668999 -0.6541433 0.3528978 -0.669002 -0.6541391 0.3529001 -0.5070203 -0.8160936 0.2773478 -0.5237215 -0.8002428 0.2921083 -0.2834516 -0.9433447 0.1724992 -0.08676755 -0.9942053 0.06346148 -0.3725656 -0.9141407 0.159818 -0.1509614 0.9883276 0.02047991 0.3156661 -0.9461299 -0.07206439 0.1353595 -0.9907252 -0.011891 0.3391715 -0.9366863 -0.08707255 0.5404078 -0.8258407 -0.1610797 0.710039 -0.6670261 -0.2256564 0.540408 -0.8258403 -0.161081 -0.5404178 0.8258341 0.1610801 -0.3069309 0.9487398 0.07540583 0.8382609 -0.4696372 -0.2770555 0.7100267 -0.667042 -0.2256483 -0.7100305 0.667036 0.225654 -0.5403994 0.8258463 0.1610788 0.9177785 -0.2451903 -0.3123531 0.8382566 -0.4696461 -0.277053 -0.8382564 0.4696434 0.2770583 -0.7100327 0.6670337 0.225654 0.9441133 -0.006622016 -0.3295544 0.917784 -0.2451596 -0.3123612 -0.9177813 0.2451702 0.3123604 -0.8382593 0.4696385 0.2770581 0.9157909 0.2322962 -0.327667 0.9441139 -0.006640195 -0.3295525 -0.9441134 0.006633698 0.3295542 -0.9177785 0.245181 0.3123602 0.8344138 0.4578469 -0.3068056 0.9157907 0.2322948 -0.3276683 0.7045756 0.6570228 -0.268131 0.8344088 0.4578567 -0.3068048 -0.9157916 -0.2322899 0.3276692 -0.9441141 0.00662446 0.3295525 0.5336952 0.8181936 -0.213843 0.7045858 0.6570114 -0.2681322 0.2920401 0.9470073 -0.1337532 0.5336925 0.8181949 -0.2138443 -0.8344131 -0.4578498 0.3068034 0.1086133 0.9915544 -0.07087391 -0.9157924 -0.232289 0.3276678 0.2971349 0.9453085 -0.1345466 0.1029562 0.9922448 -0.06964331 -0.8344174 -0.4578397 0.3068071 -0.7045808 -0.6570175 0.2681304 -0.7045758 -0.6570234 0.2681291 -0.5336886 -0.8181986 0.2138407 -0.5336938 -0.8181939 0.2138451 -0.3779331 -0.9114488 0.1625663 0.8595054 0.4610359 -0.2206726 0.8595024 0.4610428 -0.2206704 0.8725386 0.4626377 -0.1569805 -0.7316645 0.6650258 0.1496919 -0.7325083 0.664127 0.149556 0.7281256 0.659927 -0.1852822 0.7027342 0.6858644 -0.1890893 0.762099 0.6316563 -0.142182 0.5519119 0.8204327 -0.1492766 -0.8644787 0.4671469 0.1856078 -0.8649745 0.4662892 0.1854546 0.5512033 0.8208976 -0.1493393 -0.9470593 0.2422278 0.2107237 0.3884356 0.9143359 -0.11449 -0.9472401 0.2416302 0.2105971 -0.9746713 0.003348231 0.2236171 -0.9746872 0.003100812 0.2235515 -0.9457839 -0.23558 0.2235955 -0.9457572 -0.2357332 0.2235473 -0.8619771 -0.4611692 0.2105196 -0.8621674 -0.4607306 0.2107003 -0.7285276 -0.6594039 0.1855643 -0.7281283 -0.6599248 0.1852798 -0.5524184 -0.8200345 0.1495909 -0.5519002 -0.8204409 0.149275 -0.3078463 -0.9464843 0.09694403 -0.1755488 -0.9820255 0.06934505 0.1093378 -0.9940027 0.001973927 0.3789295 -0.9233726 -0.0616095 0.5562358 -0.8243575 -0.105055 0.5550374 -0.8252544 -0.1043488 0.7308247 -0.6660786 -0.1491129 0.7316702 -0.665019 -0.1496946 0.8920091 -0.4296711 -0.1403662 0.8621079 -0.4675967 -0.1952519 0.8515584 -0.4917608 -0.1817128 0.9579539 -0.2410263 -0.1556623 0.9579609 -0.2410023 -0.1556562 0.9444897 -0.2426761 -0.2214668 0.9444919 -0.2426608 -0.2214741 -0.1107767 0.9938446 -0.001212656 -0.3801798 0.9226284 0.06496459 0.98617 -0.001946568 -0.1657257 0.986169 -0.001958489 -0.1657321 0.9720301 -0.003695964 -0.2348276 0.9720288 -0.003682255 -0.234833 -0.4008316 0.9137091 0.06685769 0.957137 0.2372208 -0.1661779 0.9431459 0.2354946 -0.2345594 0.9571356 0.2372281 -0.1661754 0.943141 0.2355121 -0.2345619 -0.5562472 0.8243488 0.1050631 -0.5574899 0.8235225 0.1049563 0.8725349 0.4626449 -0.1569793 0.8814533 0.4639044 -0.08850359 0.8808979 0.464906 -0.08877611 -0.7455759 0.6629147 0.0682705 -0.7467819 0.6615858 0.06797897 0.722124 0.686213 -0.08745712 0.7492035 0.6577173 -0.07811665 0.5633589 0.8230676 -0.0720188 -0.8814656 0.4645981 0.08465868 -0.882561 0.462588 0.08425366 0.562978 0.8233234 -0.07207328 0.3215863 0.9452364 -0.05577069 -0.9659795 0.2396925 0.09711462 0.3567865 0.9327701 -0.05141472 -0.9668489 0.2364395 0.09643465 0.1181324 0.9925047 -0.03129208 -0.9945781 0.001074433 0.1039875 -0.9945371 0.002665936 0.1043503 -0.9659917 -0.2361954 0.1052232 -0.9657078 -0.237506 0.1048775 -0.881009 -0.4624754 0.09969812 -0.8814767 -0.4615184 0.09999966 -0.7456416 -0.6603856 0.08893579 -0.745253 -0.660849 0.08875012 -0.566184 -0.8210707 0.07265502 -0.56615 -0.8210952 0.0726425 -0.3824186 -0.9218606 0.06268382 -0.3533129 -0.9340563 0.05204874 -0.08485025 -0.996015 0.02747446 0.1131674 -0.9935733 0.002351284 0.3080878 -0.9512767 -0.01244205 0.3335464 -0.9425216 -0.02000129 0.5655794 -0.8234132 -0.0459432 0.5658653 -0.8232106 -0.04605299 0.7457167 -0.6628283 -0.06756687 0.745193 -0.6634412 -0.06732904 0.8819159 -0.4636501 -0.08516418 0.8605819 -0.5041012 -0.07266902 0.1166197 0.9926819 -0.03134721 -0.1210033 0.9926494 -0.002314984 0.9670053 -0.2396519 -0.08641678 0.9674502 -0.2376002 -0.08710056 0.9957148 -5.20425e-4 -0.09247654 0.9956386 0.002130925 -0.09327018 -0.3294907 0.9439538 0.0196774 0.9665071 0.2385988 -0.0945236 -0.5662941 0.8228735 0.04679965 0.966988 0.2368434 -0.09401863 -0.570113 0.8202701 0.046135 0.886954 -0.4618554 0.001506328 0.8993224 -0.4372638 -0.004424333 0.9715999 -0.236231 -0.01373577 0.9999744 0.00373876 -0.006096661 0.9985045 -0.05460947 0.002571225 -0.400811 0.9161554 -0.003141701 -0.134281 0.9909368 0.003601074 -0.09893828 0.9950311 0.0111491 0.8920613 0.4516887 -0.01428753 0.9686935 0.2482579 -0.001076698 0.9631082 0.2690572 -0.005546092 -0.7534409 0.6575023 0.004185616 -0.5647184 0.8252795 0.002617418 -0.5222406 0.8527347 0.01040929 0.5759507 0.8173861 -0.01268661 0.7417623 0.6706629 5.61908e-5 0.7627109 0.6467035 0.006830096 -0.8899953 0.4559441 0.004857063 -0.748508 0.6631193 0.002949297 -0.9071177 0.4207254 0.01129549 0.1228365 0.9923753 -0.01012176 0.3488372 0.9371793 0.00279957 0.374819 0.9270571 0.008709847 -0.9697515 0.2440746 -0.003098547 -0.9999822 0.002864003 0.005227863 -0.9987182 0.04902583 0.01258593 -0.9716139 -0.2362464 0.0124163 -0.9631137 -0.2690531 0.004749715 -0.887169 -0.4614272 -0.004025161 -0.7505887 -0.6606658 0.01172524 -0.7626426 -0.6466242 0.01592463 -0.5711697 -0.8208165 -0.005078911 -0.3747941 -0.9269996 0.01417922 -0.3567904 -0.9341329 0.009817481 -0.1656213 -0.9861813 -0.004012465 0.07426452 -0.9972054 0.008139789 0.4111394 -0.9115714 0.001439869 0.5688213 -0.8223887 -0.01092988 0.7500546 -0.6613655 -0.003723323 0.7111613 -0.70301 0.005167543 0.01592493 0.987116 0.1592121 0.01760673 0.9879335 0.1538754 0.01679468 0.9871647 0.1588203 0.01525092 0.9814766 0.1909743 0.01535946 0.9868367 0.160989 0.01524913 0.98668 0.1619572 0.01592153 0.987116 0.1592128 0.01733845 0.9933369 0.1139352 0.01592093 0.987116 0.1592118 0.01592099 0.9871162 0.1592111 0.01384752 0.9865185 0.1630636 0.016052 0.9870929 0.1593427 0.01603215 0.9870666 0.1595078 0.01614373 0.9871266 0.1591241 0.0160014 0.9871558 0.1589574 0.0301218 0.9877291 0.1532444 0.04585313 0.9877953 0.1488555 0 0 1 -2.18678e-6 0 1 3.00608e-6 0 1 2.37923e-6 0 1 6.01258e-6 0 1 -9.75467e-4 2.11987e-5 0.9999995 6.51109e-4 -2.63983e-4 0.9999998 + + + + + + + + + + + + + + +

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

+
+
+
+ + + + -0.2685 -0.09419995 -0.1132 -0.2685 -0.08606696 -0.1132 -0.1019999 -0.09419995 -0.1132 -0.1019999 -0.08606696 -0.1132 -0.2685 -0.09920001 -0.1182 -0.1019999 -0.09920001 -0.1182 -0.2685 -0.09920001 -0.1263329 -0.1019999 -0.09920001 -0.1263329 -0.1019999 -0.1407999 -0.1263329 -0.1019999 -0.1407999 -0.1182 -0.2685 -0.1407999 -0.1182 -0.2685 -0.1407999 -0.1263329 -0.2685 -0.1457999 -0.1132 -0.1019999 -0.1457999 -0.1132 -0.2685 -0.153933 -0.1132 -0.1019999 -0.153933 -0.1132 -0.1019999 -0.09920001 -0.06659996 -0.2685 -0.09920001 -0.06659996 -0.1019999 -0.09920001 -0.05846697 -0.2685 -0.09920001 -0.05846697 -0.2685 -0.09419995 -0.07159996 -0.1019999 -0.09419995 -0.07159996 -0.2685 -0.08606696 -0.07159996 -0.1019999 -0.08606696 -0.07159996 -0.2685 -0.1457999 -0.07159996 -0.2685 -0.153933 -0.07159996 -0.1019999 -0.1457999 -0.07159996 -0.1019999 -0.153933 -0.07159996 -0.2685 -0.1407999 -0.06659996 -0.1019999 -0.1407999 -0.06659996 -0.2685 -0.1407999 -0.05846697 -0.1019999 -0.1407999 -0.05846697 -0.2685 -0.155933 -0.1112 -0.1019999 -0.155933 -0.1112 -0.2685 -0.155933 -0.07359999 -0.1019999 -0.155933 -0.07359999 -0.2685 -0.1012 -0.128333 -0.1019999 -0.1012 -0.128333 -0.2685 -0.1388 -0.128333 -0.1019999 -0.1388 -0.128333 -0.2685 -0.08406698 -0.07359999 -0.1019999 -0.08406698 -0.07359999 -0.2685 -0.08406698 -0.1112 -0.1019999 -0.08406698 -0.1112 -0.2685 -0.1388 -0.05646699 -0.1019999 -0.1388 -0.05646699 -0.2685 -0.1012 -0.05646699 -0.1019999 -0.1012 -0.05646699 -0.1019999 -0.09056699 -0.128333 -0.1019999 -0.08406698 -0.121833 -0.1019999 -0.155933 -0.121833 -0.1019999 -0.149433 -0.128333 -0.1019999 -0.08406698 -0.062967 -0.1019999 -0.09056699 -0.05646699 -0.1019999 -0.155933 -0.062967 -0.1019999 -0.149433 -0.05646699 -0.09299999 -0.155933 -0.121833 -0.09299999 -0.149433 -0.128333 -0.09299999 -0.149433 -0.05646699 -0.09299999 -0.155933 -0.062967 -0.09299999 -0.08406698 -0.062967 -0.09299999 -0.09056699 -0.05646699 -0.09299999 -0.09056699 -0.128333 -0.09299999 -0.08406698 -0.121833 -0.2495 -0.1407999 0.1182 -0.083 -0.1407999 0.1182 -0.2495 -0.1407999 0.1263329 -0.083 -0.1407999 0.1263329 -0.083 -0.1457999 0.1132 -0.2495 -0.1457999 0.1132 -0.2495 -0.153933 0.1132 -0.083 -0.153933 0.1132 -0.083 -0.09920001 0.1182 -0.2495 -0.09920001 0.1182 -0.083 -0.09920001 0.1263329 -0.2495 -0.09920001 0.1263329 -0.2495 -0.09419995 0.1132 -0.083 -0.09419995 0.1132 -0.2495 -0.08606696 0.1132 -0.083 -0.08606696 0.1132 -0.2495 -0.09419995 0.07159996 -0.2495 -0.08606696 0.07159996 -0.083 -0.09419995 0.07159996 -0.083 -0.08606696 0.07159996 -0.2495 -0.09920001 0.06659996 -0.083 -0.09920001 0.06659996 -0.2495 -0.09920001 0.05846697 -0.083 -0.09920001 0.05846697 -0.083 -0.1407999 0.05846697 -0.083 -0.1407999 0.06659996 -0.2495 -0.1407999 0.06659996 -0.2495 -0.1407999 0.05846697 -0.2495 -0.1457999 0.07159996 -0.083 -0.1457999 0.07159996 -0.2495 -0.153933 0.07159996 -0.083 -0.153933 0.07159996 -0.2495 -0.155933 0.07359999 -0.083 -0.155933 0.07359999 -0.2495 -0.155933 0.1112 -0.083 -0.155933 0.1112 -0.2495 -0.1012 0.05646699 -0.083 -0.1012 0.05646699 -0.2495 -0.1388 0.05646699 -0.083 -0.1388 0.05646699 -0.2495 -0.08406698 0.1112 -0.083 -0.08406698 0.1112 -0.2495 -0.08406698 0.07359999 -0.083 -0.08406698 0.07359999 -0.083 -0.149433 0.128333 -0.083 -0.155933 0.121833 -0.074 -0.149433 0.128333 -0.074 -0.155933 0.121833 -0.083 -0.1388 0.128333 -0.2495 -0.1388 0.128333 -0.2495 -0.1012 0.128333 -0.083 -0.1012 0.128333 -0.083 -0.08406698 0.121833 -0.083 -0.09056699 0.128333 -0.074 -0.08406698 0.121833 -0.074 -0.09056699 0.128333 -0.083 -0.09056699 0.05646699 -0.083 -0.08406698 0.062967 -0.083 -0.155933 0.062967 -0.083 -0.149433 0.05646699 -0.074 -0.155933 0.062967 -0.074 -0.149433 0.05646699 -0.074 -0.09056699 0.05646699 -0.074 -0.08406698 0.062967 -0.276 -0.09419995 -0.02079999 -0.276 -0.08606696 -0.02079999 -0.1095 -0.09419995 -0.02079999 -0.1095 -0.08606696 -0.02079999 -0.276 -0.09920001 -0.02579998 -0.1095 -0.09920001 -0.02579998 -0.276 -0.09920001 -0.03393298 -0.1095 -0.09920001 -0.03393298 -0.1095 -0.1407999 -0.03393298 -0.1095 -0.1407999 -0.02579998 -0.276 -0.1407999 -0.02579998 -0.276 -0.1407999 -0.03393298 -0.276 -0.1457999 -0.02079999 -0.1095 -0.1457999 -0.02079999 -0.276 -0.153933 -0.02079999 -0.1095 -0.153933 -0.02079999 -0.276 -0.09920001 0.02579998 -0.276 -0.09920001 0.03393298 -0.1095 -0.09920001 0.02579998 -0.1095 -0.09920001 0.03393298 -0.276 -0.09419995 0.02079999 -0.1095 -0.09419995 0.02079999 -0.276 -0.08606696 0.02079999 -0.1095 -0.08606696 0.02079999 -0.276 -0.1457999 0.02079999 -0.276 -0.153933 0.02079999 -0.1095 -0.1457999 0.02079999 -0.1095 -0.153933 0.02079999 -0.276 -0.1407999 0.02579998 -0.1095 -0.1407999 0.02579998 -0.276 -0.1407999 0.03393298 -0.1095 -0.1407999 0.03393298 -0.276 -0.155933 -0.01879996 -0.1095 -0.155933 -0.01879996 -0.276 -0.155933 0.01879996 -0.1095 -0.155933 0.01879996 -0.276 -0.1012 -0.03593295 -0.1095 -0.1012 -0.03593295 -0.276 -0.1388 -0.03593295 -0.1095 -0.1388 -0.03593295 -0.276 -0.08406698 0.01879996 -0.1095 -0.08406698 0.01879996 -0.276 -0.08406698 -0.01879996 -0.1095 -0.08406698 -0.01879996 -0.276 -0.1388 0.03593295 -0.1095 -0.1388 0.03593295 -0.276 -0.1012 0.03593295 -0.1095 -0.1012 0.03593295 -0.1095 -0.09056699 -0.03593295 -0.1095 -0.08406698 -0.02943295 -0.1095 -0.155933 -0.02943295 -0.1095 -0.149433 -0.03593295 -0.1095 -0.08406698 0.02943295 -0.1095 -0.09056699 0.03593295 -0.1095 -0.155933 0.02943295 -0.1095 -0.149433 0.03593295 -0.1005 -0.155933 -0.02943295 -0.1005 -0.149433 -0.03593295 -0.1005 -0.149433 0.03593295 -0.1005 -0.155933 0.02943295 -0.1005 -0.09056699 0.03593295 -0.1005 -0.08406698 0.02943295 -0.1005 -0.09056699 -0.03593295 -0.1005 -0.08406698 -0.02943295 + + + + + + + + + + 0 0 -1 0 0.7071073 -0.7071064 0 0.7071057 -0.7071079 0 1 0 0 -1 0 0 -0.7071057 -0.707108 0 -0.7071073 -0.7071063 0 0.7071057 0.707108 0 0.7071073 0.7071063 0 0 1 0 -0.7071073 0.7071064 0 -0.7071057 0.7071079 0 -0.7071036 -0.7071101 0 -0.7071115 -0.7071021 0 -0.7071114 0.7071022 0 -0.7071036 0.70711 0 0.7071114 -0.7071022 0 0.7071036 -0.70711 0 -0.7071075 -0.7071061 0 -0.7071076 -0.707106 0 0.7071095 0.7071042 0 0.7071076 0.707106 0 0.7071075 -0.7071061 0 0.7071095 -0.707104 0 -0.7071069 0.7071068 0 -0.7071069 0.7071067 -1 0 0 -1 -2.44441e-6 0 -1 4.41874e-6 0 -1 2.44441e-6 0 0 0.7071029 0.7071107 0 0.7071108 0.7071027 -1 1.36856e-6 0 -1 -1.36857e-6 0 -1 -4.14512e-7 0 -1 9.5439e-7 0 -1 4.14512e-7 0 0 -0.7071082 -0.7071054 0 -0.7071076 -0.7071061 0 -0.7071082 0.7071054 0 -0.7071076 0.7071061 0 0.7071076 0.7071061 0 0.7071068 0.7071068 -6.59211e-7 0 1 0 0.7071076 -0.7071061 0 0.7071068 -0.7071068 8.78948e-7 0 -1 2.75214e-6 0 -1 1 0 0 1 1.99372e-6 0 1 -2.42038e-7 0 0 -0.7071057 0.7071079 0 0.7071074 0.7071063 0 0.7071057 -0.7071079 0 -0.7071074 -0.7071063 0 -0.7071115 -0.707102 0 -0.7071036 0.7071099 0 0.7071108 -0.7071028 0 0.707103 -0.7071107 0 -0.7071069 -0.7071068 0 -0.7071069 -0.7071067 0 0.7071076 0.707106 0 0.7071096 -0.707104 0 -0.7071079 0.7071058 0 -0.7071075 0.7071061 0 -0.7071076 0.707106 -1 -1.22221e-6 0 -1 1.22221e-6 0 0 0.7071036 0.7071101 0 0.7071115 0.707102 0 0.7071071 0.7071065 -1 1.65805e-6 0 -1 -4.77195e-7 0 -1 4.77195e-7 0 -1 -1.65805e-6 0 8.78949e-7 0 1 2.75214e-6 0 1 0 -0.7071079 -0.7071058 0 0.7071071 -0.7071065 -4.39474e-7 0 -1 1 1.24607e-7 0 0 0.7071076 -0.7071059 0 0.7071061 -0.7071076 0 -0.7071061 -0.7071076 0 -0.7071076 -0.7071059 0 0.7071061 0.7071076 0 0.7071076 0.7071059 0 -0.7071076 0.7071059 0 -0.7071061 0.7071076 0 -0.7071029 -0.7071107 0 -0.7071108 -0.7071028 0 -0.7071108 0.7071028 0 -0.7071029 0.7071107 0 0.7071029 -0.7071107 0 0.7071088 0.7071048 0 0.7071069 0.7071068 0 0.7071069 -0.7071068 0 0.7071088 -0.7071048 -1 -7.15698e-6 0 -1 7.15695e-6 0 -1 -4.88882e-6 0 -1 1.9332e-6 0 -1 -1.9332e-6 0 -1 4.88882e-6 0 0 0.7071108 0.7071028 -1 1.2407e-6 0 -1 4.77194e-7 0 -1 -5.47426e-6 0 -1 5.47428e-6 0 -1 -4.77195e-7 0 -1 -1.2407e-6 0 -1 -6.20352e-7 0 0 -0.7071068 -0.7071068 0 -0.7071068 0.7071068 0 0.7071061 0.7071076 0 0.7071061 -0.7071076 0 0 -1 + + + + + + + + + + + + + + +

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

+
+
+
+
+ + + + + 0.6859207 -0.3240135 0.6515582 7.481132 0.7276763 0.3054208 -0.6141704 -6.50764 0 0.8953956 0.4452714 5.343665 0 0 0 1 + + + + -0.2908646 -0.7711008 0.5663932 4.076245 0.9551712 -0.1998834 0.2183912 1.005454 -0.05518906 0.6045247 0.7946723 5.903862 0 0 0 1 + + + + 1 0 0 0 0 1 0 0 0 0 1 0 0 0 0 1 + + + + + + + + + + 1 0 0 0 0 1 0 0 0 0 1 0 0 0 0 1 + + + + + + + + + + 1 0 0 0 0 1 0 0 0 0 1 0 0 0 0 1 + + + + + + + + + + 1 0 0 0 0 1 0 0 0 0 1 0 0 0 0 1 + + + + + + + + + + + + + +
\ No newline at end of file diff --git a/kuka_kr5_support/meshes/kr5_arc/visual/link_4.dae b/kuka_kr5_support/meshes/kr5_arc/visual/link_4.dae new file mode 100644 index 000000000..3e874ca11 --- /dev/null +++ b/kuka_kr5_support/meshes/kr5_arc/visual/link_4.dae @@ -0,0 +1,275 @@ + + + + + Blender User + Blender 2.79.0 commit date:2017-09-11, commit time:10:43, hash:5bd8ac9abfa + + 2017-11-10T20:08:13 + 2017-11-10T20:08:13 + + Z_UP + + + + + + + 49.13434 + 1.777778 + 0.1 + 100 + + + + + + 0 + 0 + 0 + + + + + + + + + 1 1 1 + 1 + 0 + 0.00111109 + + + + + 0 + 0 + 8192 + 1 + 1 + 1 + 1 + 0 + 0 + 0 + 1 + 29.99998 + 75 + 0.15 + 1 + 0 + 1 + 2 + 1.000799 + 30.002 + 1 + 3 + 0.04999995 + 2880 + 3 + 1 + 0 + 0 + 2 + 1 + 1 + 1 + 0 + 1 + 0.1 + 0.1 + 1 + 0.000999987 + 1 + 0 + 0 + 1 + 1 + 1 + 1 + 1 + 1 + 1 + 2 + 1 + 1 + 1 + 1 + 0 + + + + + + + + + + + + 0 0 0 1 + + + 0 0 0 1 + + + 1 0.4980392 0 1 + + + 0.5 0.5 0.5 1 + + + 0 + + + 1 1 1 1 + + + 1 + + + + + + + + + + + 0 0 0 1 + + + 0 0 0 1 + + + 0 0 0 1 + + + 0.5 0.5 0.5 1 + + + 0 + + + 1 1 1 1 + + + 1 + + + + + + + + + + + + + + + + + + + -0.05723679 0.0330457 -0.351 -0.06037747 0.02688175 -0.351 -0.0330457 0.05723679 -0.351 0.05346906 -0.0388475 -0.351 0.05723679 -0.0330457 -0.351 0.06037747 -0.02688175 -0.351 -0.04911547 -0.04422378 -0.351 -0.04422378 -0.04911547 -0.351 -0.05346906 -0.0388475 -0.351 -0.02688175 0.06037747 -0.351 -0.02042335 0.06285667 -0.351 -0.0388475 -0.05346906 -0.351 -0.0330457 -0.05723679 -0.351 0.06285667 -0.02042335 -0.351 0.06464713 -0.01374113 -0.351 -0.05723679 -0.0330457 -0.351 -0.06037747 -0.02688175 -0.351 0.06572932 -0.006908416 -0.351 -0.02688175 -0.06037747 -0.351 0 0.06609141 -0.351 -0.006908416 0.06572932 -0.351 -0.01374113 0.06464713 -0.351 -0.06285667 -0.02042335 -0.351 -0.02042335 -0.06285667 -0.351 -0.01374113 -0.06464713 -0.351 0.06609141 0 -0.351 0.06572932 0.006908416 -0.351 -0.006908416 -0.06572932 -0.351 -0.06572932 -0.006908416 -0.351 -0.06464713 -0.01374113 -0.351 -0.06609141 0 -0.351 0.006908416 -0.06572932 -0.351 0.02042335 -0.06285667 -0.351 0.02688175 0.06037747 -0.351 0 -0.06609141 -0.351 0.02042335 0.06285667 -0.351 0.01374113 0.06464713 -0.351 0.006908416 0.06572932 -0.351 0.06464713 0.01374113 -0.351 0.06285667 0.02042335 -0.351 0.06037747 0.02688175 -0.351 0.05346906 0.0388475 -0.351 0.05723679 0.0330457 -0.351 0.01374113 -0.06464713 -0.351 -0.06464713 0.01374113 -0.351 -0.06572932 0.006908416 -0.351 -0.06285667 0.02042335 -0.351 0.04911547 0.04422378 -0.351 0.0388475 0.05346906 -0.351 0.0330457 0.05723679 -0.351 0.04422378 0.04911547 -0.351 0.02688175 -0.06037747 -0.351 0.0330457 -0.05723679 -0.351 0.0388475 -0.05346906 -0.351 0.04911547 -0.04422378 -0.351 0.04422378 -0.04911547 -0.351 -0.04911547 0.04422378 -0.351 -0.05346906 0.0388475 -0.351 -0.04422378 0.04911547 -0.351 -0.0388475 0.05346906 -0.351 -0.04119527 -0.0457521 -0.4035013 -0.03620278 -0.04975461 -0.403501 -0.03126567 -0.05301284 -0.4035012 -0.02500247 -0.05626183 -0.403501 -0.01901495 -0.05852252 -0.4035011 -0.01335382 -0.06007981 -0.4035011 -0.006411314 -0.06122732 -0.4035009 5.7061e-4 -0.06154334 -0.4035012 0.006387054 -0.06119811 -0.403501 0.01223772 -0.06031703 -0.4035012 0.01847523 -0.05870753 -0.403501 0.02500253 -0.05626183 -0.403501 0.03126561 -0.0530129 -0.4035012 0.03666073 -0.04943406 -0.4035009 0.04117435 -0.0457288 -0.4035012 0.04573994 -0.04120296 -0.4035009 0.04978215 -0.03616887 -0.4035012 0.05301272 -0.03126597 -0.4035009 0.05595415 -0.02563768 -0.403501 0.05855214 -0.01902496 -0.4035012 0.06031703 -0.01223796 -0.4035009 0.06126582 -0.005865514 -0.4035012 0.0615279 0 -0.4035009 0.06122821 0.006435275 -0.4035013 0.06019425 0.01276576 -0.403501 0.05855214 0.01902496 -0.4035012 0.05595415 0.02563768 -0.403501 0.05329006 0.0307672 -0.403501 0.0498076 0.03618711 -0.4035013 0.04570478 0.0411936 -0.403501 0.04119527 0.0457521 -0.4035013 0.03620278 0.04975461 -0.403501 0.03126567 0.05301284 -0.4035012 0.02500253 0.05626183 -0.403501 0.01901495 0.05852252 -0.4035011 0.01335382 0.06007981 -0.4035011 0.007019639 0.06114035 -0.4035009 0 0.06155693 -0.403501 -0.006387054 0.06119811 -0.403501 -0.01223754 0.06031709 -0.4035012 -0.01847523 0.05870753 -0.403501 -0.02500253 0.05626183 -0.403501 -0.03126561 0.0530129 -0.4035012 -0.03666061 0.04943412 -0.4035009 -0.04117435 0.0457288 -0.4035012 -0.04574 0.0412029 -0.4035009 -0.04978215 0.03616887 -0.4035012 -0.05301272 0.03126597 -0.4035009 -0.05595415 0.02563768 -0.403501 -0.05855214 0.01902496 -0.4035012 -0.06031703 0.01223796 -0.4035009 -0.06119704 0.006432056 -0.4035012 -0.06153738 6.40516e-4 -0.4035008 -0.06122815 -0.006435394 -0.4035013 -0.06019425 -0.01276582 -0.403501 -0.05855214 -0.01902496 -0.4035012 -0.05595415 -0.02563768 -0.403501 -0.05329006 -0.0307672 -0.403501 -0.0498076 -0.03618711 -0.4035013 -0.04570478 -0.0411936 -0.403501 -0.06105154 0.00741297 -0.4195 -0.06105154 -0.00741297 -0.4195 -0.05750346 0.02180814 -0.4195 0 0.06149995 -0.4195 -0.05061346 0.03493595 -0.4195 0.01471787 0.05971288 -0.4195 -0.04078203 0.04603338 -0.4195 0.02858042 0.05445551 -0.4195 -0.02858042 0.05445551 -0.4195 0.04078203 0.04603338 -0.4195 -0.01471787 0.05971288 -0.4195 0.05061346 0.03493595 -0.4195 0.05750346 0.02180814 -0.4195 0.06105154 0.00741297 -0.4195 0.06105154 -0.00741297 -0.4195 0.05750346 -0.02180814 -0.4195 0.05061346 -0.03493595 -0.4195 0.04078203 -0.04603338 -0.4195 0.02858042 -0.05445551 -0.4195 0.01471787 -0.05971288 -0.4195 0 -0.06149995 -0.4195 -0.01471787 -0.05971288 -0.4195 -0.02858042 -0.05445551 -0.4195 -0.04078203 -0.04603338 -0.4195 -0.05061346 -0.03493595 -0.4195 -0.05750346 -0.02180814 -0.4195 0.04815334 -0.01826214 -0.4195 0.05112451 -0.006207585 -0.4195 0 0.05149996 -0.4195 0.01232475 0.05000346 -0.4195 -0.03415077 -0.03854829 -0.4195 -0.04238367 -0.02925533 -0.4195 0.05112451 0.006207585 -0.4195 -0.02393323 -0.04560095 -0.4195 -0.04815334 -0.01826214 -0.4195 -0.01232475 -0.05000346 -0.4195 0.02393323 0.04560095 -0.4195 -0.05112451 -0.006207585 -0.4195 0.04815334 0.01826214 -0.4195 0.03415077 0.03854829 -0.4195 0 -0.05149996 -0.4195 0.04238367 0.02925533 -0.4195 -0.05112451 0.006207585 -0.4195 0.01232475 -0.05000346 -0.4195 -0.04815334 0.01826214 -0.4195 0.02393323 -0.04560095 -0.4195 -0.04238367 0.02925533 -0.4195 0.03415077 -0.03854829 -0.4195 -0.03415077 0.03854829 -0.4195 0.04238367 -0.02925533 -0.4195 -0.02393323 0.04560095 -0.4195 -0.01232475 0.05000346 -0.4195 -0.05112451 0.006207585 -0.4445 -0.05112451 -0.006207585 -0.4445 -0.04815334 0.01826214 -0.4445 0.01232475 0.05000346 -0.4445 0 0.05149996 -0.4445 -0.04238367 0.02925533 -0.4445 -0.03415077 0.03854829 -0.4445 0.02393323 0.04560095 -0.4445 -0.02393323 0.04560095 -0.4445 0.03415077 0.03854829 -0.4445 -0.01232475 0.05000346 -0.4445 0.04238367 0.02925533 -0.4445 0.04815334 0.01826214 -0.4445 0.05112451 0.006207585 -0.4445 0.05112451 -0.006207585 -0.4445 0.04815334 -0.01826214 -0.4445 0.04238367 -0.02925533 -0.4445 0.03415077 -0.03854829 -0.4445 0.02393323 -0.04560095 -0.4445 0.01232475 -0.05000346 -0.4445 0 -0.05149996 -0.4445 -0.01232475 -0.05000346 -0.4445 -0.02393323 -0.04560095 -0.4445 -0.03415077 -0.03854829 -0.4445 -0.04238367 -0.02925533 -0.4445 -0.04815334 -0.01826214 -0.4445 -0.05971288 0.01471787 -0.4445 -0.05445551 0.02858042 -0.4445 0.00741297 -0.06105154 -0.4445 0.02180814 -0.05750346 -0.4445 0.04603338 0.04078203 -0.4445 0.03493595 0.05061346 -0.4445 0.05445551 0.02858042 -0.4445 -0.06149995 0 -0.4445 0.02180814 0.05750346 -0.4445 0.05971288 0.01471787 -0.4445 -0.00741297 -0.06105154 -0.4445 0.00741297 0.06105154 -0.4445 0.06149995 0 -0.4445 -0.05971288 -0.01471787 -0.4445 -0.02180814 -0.05750346 -0.4445 -0.00741297 0.06105154 -0.4445 -0.05445551 -0.02858042 -0.4445 -0.03493595 -0.05061346 -0.4445 0.05971288 -0.01471787 -0.4445 -0.04603338 -0.04078203 -0.4445 -0.02180814 0.05750346 -0.4445 0.05445551 -0.02858042 -0.4445 -0.03493595 0.05061346 -0.4445 0.04603338 -0.04078203 -0.4445 -0.04603338 0.04078203 -0.4445 0.03493595 -0.05061346 -0.4445 0.04063922 0.0461595 -0.449523 0.02836334 0.05456888 -0.449523 0.01442706 0.05978381 -0.449523 -0.06149995 0 -0.4508968 -0.06014722 -0.01282799 -0.4508858 -3.5376e-4 0.06149893 -0.449523 -0.01511389 0.05961388 -0.449523 -0.02898925 0.05423897 -0.449523 -0.05873793 -0.01822358 -0.4508878 -0.05684572 -0.02346938 -0.4508878 -0.04116755 0.04568892 -0.449523 -0.05093592 -0.03446418 -0.449523 -0.05285382 -0.03144389 -0.4508834 -0.05093705 -0.03448086 -0.4508855 -0.04116755 -0.04568892 -0.449523 -0.05541515 0.02667224 -0.4509717 -0.05093592 0.03446418 -0.449523 -0.05093592 0.03446418 -0.4510155 -0.02898925 -0.05423897 -0.449523 -0.01511389 -0.05961388 -0.449523 -0.05871087 0.01831066 -0.4509346 -3.5376e-4 -0.06149893 -0.449523 -0.06075268 0.009558022 -0.4509049 0.01442706 -0.05978381 -0.449523 0.02836334 -0.05456888 -0.449523 0.04063922 -0.0461595 -0.449523 0.05053603 -0.03504782 -0.449523 0.05747449 -0.0218845 -0.449523 0.06104826 -0.00743997 -0.449523 0.06104826 0.00743997 -0.449523 0.05747449 0.0218845 -0.449523 0.05053603 0.03504782 -0.449523 -0.05090999 0.03772479 -0.4510046 -0.06346768 0.02225172 -0.450911 -0.06603395 0.002197444 -0.4508878 -0.0635088 -0.02192807 -0.4509114 -0.05093622 -0.03640681 -0.4508861 -0.05093592 -0.03641343 -0.449523 -0.05093592 -0.0409972 -0.4518478 -0.0509358 -0.04427832 -0.453369 -0.05093592 -0.04909306 -0.4508588 -0.05093592 -0.04768657 -0.4611401 0.03662663 -0.05160915 -0.449523 -0.03255546 -0.05456703 -0.449523 0.03258812 -0.05454331 -0.449523 0.005715072 0.06327772 -0.449523 -1.07674e-4 0.0635392 -0.449523 -0.01138514 -0.06251239 -0.449523 -0.01688438 0.06125444 -0.449523 -0.02756768 0.05724489 -0.449523 0.0222029 -0.05954456 -0.449523 0.01703685 0.06122308 -0.449523 0 -0.06353706 -0.449523 -0.03746277 0.05133289 -0.449523 -0.04592424 0.04390805 -0.449523 0.03629034 0.05195111 -0.449523 -0.05093592 0.03762364 -0.449523 0.05187219 0.03610491 -0.449523 0.05791819 0.0235846 -0.449523 0.06192845 0.01420211 -0.449523 0.06192845 -0.01174455 -0.449523 0.05841702 -0.02255153 -0.449523 0.05187219 -0.03610491 -0.449523 -0.04183608 -0.04782426 -0.449523 -0.05000001 0.03879719 -0.4509994 -0.05000001 0.04710775 -0.450995 -0.05093592 0.04906785 -0.4510429 -0.04552692 0.04906785 -0.4510429 -0.05905175 0.03637719 -0.4511723 -0.07182002 0.01209461 -0.4798581 -0.07093214 -0.01814907 -0.4801637 -0.0580973 -0.03912848 -0.4519323 -0.05702888 -0.04590439 -0.4597422 -0.05245697 -0.04761713 -0.4616474 -0.04256951 -0.03814584 -0.530881 -0.0693317 -0.03743475 -0.5362308 -0.03778403 -0.03750824 -0.5352432 -0.06595325 -0.04117131 -0.5087653 -0.04731255 -0.0401805 -0.5160083 -0.04863214 -0.04291158 -0.4960445 -0.05799394 -0.04548108 -0.4772619 -0.04552054 -0.04908049 -0.4509509 -0.04010134 -0.0490846 -0.4509202 -0.04183608 -0.04782426 -0.4508612 -0.03255754 -0.05458837 -0.4511063 -0.03255546 -0.05456703 -0.4529158 -0.03255546 -0.05456703 -0.469523 -0.01138514 -0.06251239 -0.469523 0 -0.06353706 -0.469523 0.0222029 -0.05954456 -0.469523 0.03258812 -0.05454331 -0.469523 0.03662663 -0.05160915 -0.469523 0.04187244 -0.04623436 -0.4719678 0.05187219 -0.03610491 -0.4855 0.04376065 -0.04435408 -0.4855 0.05841702 -0.02255153 -0.4509086 0.0619471 -0.01526111 -0.4856344 0.06192845 -0.01527994 -0.4509222 0.06192845 -0.01174455 -0.4509289 0.06192845 0.01420211 -0.4509775 0.06192845 0.01527994 -0.4509795 0.06195294 0.01525521 -0.4856766 0.05791819 0.0235846 -0.4509951 0.05187219 0.03610491 -0.4855 0.04183208 0.04627388 -0.4714813 0.03665411 0.05161422 -0.4699867 0.04376065 0.04435408 -0.4855 0.01703685 0.06122308 -0.469523 0.005715072 0.06327772 -0.469523 -1.07674e-4 0.0635392 -0.469523 -0.01688438 0.06125444 -0.469523 -0.02756768 0.05724489 -0.469523 -0.02972829 0.05595403 -0.4515544 -0.03303223 0.05397999 -0.4509509 -0.03746277 0.05133289 -0.4509509 -0.03746277 0.05133289 -0.4630416 -0.03746277 0.05133289 -0.469523 -0.04592424 0.04390805 -0.4509509 -0.03695237 0.05068069 -0.4712725 -0.04863214 0.04291158 -0.4960445 -0.039038 0.04995065 -0.469523 -0.03436791 0.05397999 -0.4509509 -0.03776335 0.03750687 -0.5352667 -0.06934523 0.03745257 -0.5360344 -0.04256951 0.03814584 -0.530881 -0.04731255 0.0401805 -0.5160083 -0.06613034 0.04086017 -0.5110398 -0.05858021 0.04543453 -0.477602 -0.05092626 0.04792159 -0.4590713 -0.05093365 0.04371899 -0.4531841 -0.05093592 0.04650413 -0.4563677 -0.0681433 0.02975398 -0.4809033 -0.07388174 -0.006135821 -0.4902337 -0.06436902 -0.03544855 -0.4710755 -0.06596285 -0.04108405 -0.4974734 -0.06974869 -0.03676193 -0.536743 -0.06901228 -0.03634357 -0.5813366 -0.03001224 -0.03634548 -0.5813701 -0.03875035 -0.03665977 -0.5686237 -0.0405668 -0.03675198 -0.564918 -0.04005742 -0.0368269 -0.5619058 -0.03640806 -0.03702157 -0.5540788 -0.03190535 -0.03719556 -0.5470862 -0.02665472 -0.03734463 -0.5410919 -0.02904874 -0.03744286 -0.5371446 -0.02631533 -0.03744286 -0.5371446 -0.0343576 -0.04005289 -0.5267945 -0.0285331 -0.04002922 -0.5280252 -0.02533721 -0.04042279 -0.5273461 -0.03726243 -0.04032057 -0.5247288 -0.0389465 -0.0406847 -0.5225769 -0.03009957 -0.05220377 -0.4763675 -0.0375083 -0.04397094 -0.5083381 -0.04043877 -0.04237896 -0.5128383 -0.0340771 -0.04517215 -0.50625 -0.01998728 -0.05333667 -0.4816591 -0.03104168 -0.0459972 -0.5054656 -0.04094398 -0.04147368 -0.5166394 -0.04040694 -0.04092037 -0.5198765 -0.03824788 -0.05034142 -0.4696825 -0.03436791 -0.05397999 -0.4509509 -0.009365975 -0.04976427 -0.4971317 0 -0.04779696 -0.5032778 0.004551112 -0.04880195 -0.5001447 0.01733583 -0.05246615 -0.4869856 0.02348887 -0.05511611 -0.4769931 0.03201299 -0.05273979 -0.4734634 0.03978282 -0.03759115 -0.5347895 0.0555545 -0.03747963 -0.5357437 0.03195631 -0.03856539 -0.5279858 0.04513114 -0.04000192 -0.5173133 0.04578852 -0.04095876 -0.5103191 0.05687218 -0.03610491 -0.5355 0.06063205 -0.01899999 -0.4905 0.06189966 -0.01587748 -0.4874745 0.06133204 -0.01899999 -0.4975 0.06199997 -0.01785415 -0.4986459 0.06199997 -0.01881253 -0.5032741 0.06689625 -0.01524287 -0.53507 0.06186127 0.01591974 -0.4874867 0.06063205 0.01899999 -0.4905 0.06133204 0.01899999 -0.4975 0.06199997 0.01785415 -0.4986459 0.06199997 0.01881253 -0.5032741 0.06685072 0.01520639 -0.5345278 0.05687218 0.03610491 -0.5355 0.0555545 0.03747963 -0.5357437 0.03978282 0.03759115 -0.5347895 0.04513114 0.04000192 -0.5173133 0.03195631 0.03856539 -0.5279858 0.04578852 0.04095876 -0.5103191 0.03594958 0.05018436 -0.4733787 0.03139656 0.05328726 -0.4715734 0.02268397 0.05575674 -0.4750441 0.01693296 0.05232304 -0.4875208 0.009962201 0.04987299 -0.496307 0.0031538 0.04794251 -0.502797 -0.009016633 0.05009013 -0.4958566 -0.01397407 0.05070918 -0.4929828 -0.02083718 0.05282211 -0.4835309 -0.02523005 0.05239051 -0.4810775 -0.02890205 0.05242735 -0.4769542 -0.03875035 0.03665977 -0.5686237 -0.03000074 0.03635102 -0.5813976 -0.06899803 0.03634357 -0.5813366 -0.0405668 0.03675198 -0.564918 -0.04005742 0.0368269 -0.5619058 -0.03640806 0.03702157 -0.5540788 -0.03190529 0.03719556 -0.5470862 -0.02904874 0.03744286 -0.5371446 -0.02665472 0.03734463 -0.5410919 -0.02631533 0.03744286 -0.5371446 -0.06962007 0.03703713 -0.534997 -0.06616383 0.04071855 -0.4976639 -0.05781006 0.04579651 -0.4625278 -0.05696284 0.04355305 -0.4551339 -0.07496893 0.01809829 -0.5225508 -0.07505673 0.006044745 -0.5008417 -0.07072651 -0.02977257 -0.5019312 -0.07495552 -0.01816546 -0.5225342 -0.07229977 -0.02970069 -0.5554992 -0.06585901 -0.04203128 -0.6200403 -0.0658304 -0.04206854 -0.6168969 -0.0274555 -0.02717733 -0.5504059 -0.03237366 -0.02998709 -0.5537545 -0.03660428 -0.03322654 -0.5576151 -0.0274555 0.02717733 -0.5504059 -0.02741712 0.01816296 -0.5499596 -0.02863788 0.02016413 -0.5641575 -0.02608925 0.03824669 -0.5345153 -0.0277251 0.00762999 -0.5535412 -0.0277251 -0.00762999 -0.5535412 -0.02863788 -0.02016413 -0.5641575 -0.02999997 0.03517466 -0.58 -0.02741712 -0.01816296 -0.5499596 -0.02608925 -0.03824669 -0.5345153 -0.02172803 -0.04107177 -0.5252777 -0.02037507 -0.04076194 -0.5262882 0.01107621 -0.04072707 -0.5263151 -0.01871377 -0.04235565 -0.5210778 -0.01791727 -0.04383623 -0.5162344 -0.01858514 -0.04477524 -0.5131613 -0.05093592 -0.04319047 -0.6238479 -0.02999997 -0.04319047 -0.6238479 -0.03473412 -0.02757394 -0.5638279 -0.03875035 -0.03346967 -0.5648219 -0.03190207 -0.04800134 -0.5228824 -0.02676582 -0.04799997 -0.506647 -0.02879995 -0.04615086 -0.5053324 -0.02983832 -0.04799997 -0.5064192 -0.03443652 -0.04799997 -0.5212623 -0.02625912 -0.04640674 -0.5058293 -0.02409309 -0.04630643 -0.5066193 -0.02392601 -0.04800057 -0.5078679 -0.03645777 -0.04800033 -0.5187321 -0.02139133 -0.04589611 -0.5086161 -0.02117455 -0.04800069 -0.5110008 -0.03735405 -0.04800069 -0.5147879 -0.0197162 -0.04539966 -0.5107155 -0.02036195 -0.04799997 -0.5138754 -0.03633803 -0.04800051 -0.5108459 -0.02048772 -0.04800087 -0.5169182 -0.03356361 -0.04800075 -0.5077857 -0.02232557 -0.04800081 -0.520488 -0.02561545 -0.04800122 -0.5228294 -0.02879995 -0.04799997 -0.5234 -0.03133803 -0.04000008 -0.527793 0.0278418 -0.05222278 -0.4853292 0.02693855 -0.03949719 -0.5272608 0.04170745 -0.04591757 -0.490869 0.03889089 -0.01580566 -0.5454862 0.04563194 -0.01828777 -0.5496046 0.05460011 0.03656834 -0.5723002 0.05591279 0.03634303 -0.5756231 0.05460011 0.02645295 -0.5723002 0.05722165 0.03594052 -0.5789344 0.04563194 0.01828777 -0.5496046 0.04763782 0.03700661 -0.5546808 0.05256789 0.02213764 -0.5671574 0.04705649 0.007685661 -0.5532097 0.05460011 -0.02645295 -0.5723002 0.05256789 -0.02213764 -0.5671574 0.04705649 -0.007685661 -0.5532097 0.05722165 -0.03594052 -0.5789344 0.05591279 -0.03634303 -0.5756231 0.05460011 -0.03656834 -0.5723002 0.04763782 -0.03700661 -0.5546808 0.06090009 -0.03650027 -0.575036 0.06090027 -0.03638583 -0.581849 0.06533277 -0.03634357 -0.5813366 0.0612502 -0.0367375 -0.5655 0.05460011 -0.03700661 -0.5546808 0.06187218 -0.03610491 -0.5655 0.06349998 0.01599997 -0.4875 0.06349998 -0.01599997 -0.4875 0.07177484 -0.01547831 -0.5651785 0.06199997 -0.01599997 -0.5005 0.06199997 0.01599997 -0.5005 0.06349998 -0.01599997 -0.5005 0.06349998 -0.01899999 -0.4975 0.06349998 -0.01899999 -0.4905 0.06349998 0.01899999 -0.4905 0.06349998 0.01899999 -0.4975 0.06349998 0.01599997 -0.5005 0.0717467 0.0154463 -0.5649358 0.06187218 0.03610491 -0.5655 0.0612502 0.0367375 -0.5655 0.02693855 0.03949719 -0.5272608 0.02800381 0.05211526 -0.4856013 0.04170745 0.04591757 -0.490869 0.06090009 0.03650027 -0.575036 0.06533277 0.03634357 -0.5813366 0.06090027 0.03638583 -0.581849 0.05460011 0.03700661 -0.5546808 0.03889089 0.01580566 -0.5454862 0.01143616 0.04069119 -0.5263427 -0.02037501 0.04076194 -0.5262882 -0.03660428 0.03322654 -0.5576151 -0.03237366 0.02998709 -0.5537545 -0.03875035 0.03346967 -0.5648219 -0.03277444 0.02503085 -0.563747 -0.06585216 0.04204517 -0.6167546 -0.05093592 0.04341101 -0.6252173 -0.02999997 0.04341101 -0.6252173 -0.07231074 0.0296595 -0.5554837 -0.06585729 0.04201418 -0.6200368 -0.07698899 -4.10239e-5 -0.533076 -0.07235938 -0.02459222 -0.6275772 -0.02999997 -0.03848469 -0.6132941 -0.02999997 0.02585119 -0.5907987 -0.02999997 0.0320906 -0.5978372 -0.02999997 0.01810812 -0.5854588 -0.02999997 -0.04298609 -0.6304566 -0.02999997 -0.03899478 -0.6223505 -0.02999997 0.03646343 -0.6061648 -0.02999997 -0.03739833 -0.6312797 -0.02999997 0.009311795 -0.582128 -0.02999997 -0.01406347 -0.6618586 -0.02999997 8.8485e-4 -0.6642156 -0.02999997 -0.006734728 -0.6584236 -0.02999997 -2.61814e-5 -0.581 -0.02999997 -0.01324427 -0.6567027 -0.02999997 0.03871536 -0.6152971 -0.02999997 -0.01943248 -0.6597294 -0.02999997 -0.02136892 -0.6526637 -0.02999997 -0.03697431 -0.6441536 -0.02999997 0.03871536 -0.6247029 -0.02999997 0.04331517 -0.6287867 -0.02999997 -0.03378164 -0.6395988 -0.02999997 -0.02834039 -0.6468577 -0.02999997 -0.02687144 -0.6550127 -0.02999997 0.03646343 -0.6338352 -0.02999997 -0.03140038 -0.6510134 -0.02999997 0.03561407 -0.6460921 -0.02999997 0.0320906 -0.6421628 -0.02999997 -0.009039163 -0.5820488 -0.02999997 -0.01756602 -0.5851506 -0.02999997 -0.02514547 -0.5901375 -0.02999997 0.02585119 -0.6492013 -0.02999997 0.02833873 -0.6539035 -0.02999997 -0.03136748 -0.5967399 -0.02999997 0.01810812 -0.6545412 -0.02999997 0.01934117 -0.6597176 -0.02999997 -0.03589552 -0.6046005 -0.02999997 0.009311795 -0.657872 -0.02999997 -2.61814e-5 -0.659 -0.02202916 0.01576662 -0.5455098 -0.02229535 0.006801187 -0.5485595 -0.02229553 -0.006801784 -0.5485594 -0.02202922 -0.01576656 -0.5455098 0.009957492 -0.03037184 -0.5342782 0.009563565 -0.02670544 -0.5370976 -0.007141351 -0.03482353 -0.5308548 -0.004440784 -0.03630608 -0.5297148 -0.009562849 -0.03168994 -0.5332646 -0.002280473 -0.03692227 -0.529241 0.002280473 -0.02147167 -0.5411223 -8.62946e-4 -0.02126371 -0.5412819 0.004440784 -0.02208793 -0.5406484 0.007142126 -0.02357077 -0.5395081 -0.00995779 -0.02802401 -0.5360837 8.62109e-4 -0.03712981 -0.5290809 0.0048123 -0.03621023 -0.5297889 -0.008237481 -0.02460479 -0.5387131 0.008236289 -0.03379064 -0.5316492 -0.004813969 -0.02218484 -0.5405743 -0.05093592 -0.04298609 -0.6304566 0.0401895 -0.006819903 -0.5485578 0.05460011 -0.02213764 -0.5671574 0.04019433 0.006831049 -0.5485563 0.05460011 0.02213764 -0.5671574 0.06090003 0.03588229 -0.5790886 0.05722171 0.0362029 -0.5813093 0.05722165 0.004941999 -0.6607011 0.05722165 0.01934117 -0.6597176 0.05722165 8.8485e-4 -0.6642156 0.05722165 -0.004941999 -0.6607011 0.05722165 -0.03980857 -0.6101881 0.05722165 -0.04099994 -0.62 0.05722165 -0.04319047 -0.6238479 0.05722165 -0.03980857 -0.6298119 0.05722165 0.02329063 -0.5862577 0.05722165 -0.04298609 -0.6304566 0.05722165 0.03068894 -0.592812 0.05722165 -0.03630369 -0.6390536 0.05722165 0.03630369 -0.6009464 0.05722165 -0.01453876 -0.6583357 0.05722165 -0.01406347 -0.6618586 0.05722165 0.01453876 -0.5816643 0.05722165 0.03980857 -0.6101881 0.05722165 0.004941999 -0.5792989 0.05722165 -0.01943248 -0.6597294 0.05722165 -0.02329063 -0.6537423 0.05722165 0.04099994 -0.62 0.05722165 0.04341101 -0.6252173 0.05722165 -0.03068894 -0.647188 0.05722165 -0.03697431 -0.6441536 0.05722165 -0.02687144 -0.6550127 0.05722165 -0.03140038 -0.6510134 0.05722165 0.04331517 -0.6287867 0.05722165 0.03980857 -0.6298119 0.05722171 -0.0362029 -0.5813093 0.05722165 -0.004941999 -0.5792989 0.05722165 0.03630369 -0.6390536 0.05722165 0.03561407 -0.6460921 0.05722165 -0.01453876 -0.5816643 0.05722165 -0.02329063 -0.5862577 0.05722165 0.03068894 -0.647188 0.05722165 -0.03068894 -0.592812 0.05722165 0.02833873 -0.6539035 0.05722165 0.02329063 -0.6537423 0.05722165 -0.03630369 -0.6009464 0.05722165 0.01453876 -0.6583357 0.06090003 -0.03588229 -0.5790886 0.06600737 -0.03779309 -0.5903364 0.06329578 -0.04319047 -0.6238479 0.06685549 -0.03610491 -0.586857 0.06349998 0.01348996 -0.4960494 0.06349998 -0.01357978 -0.4960575 0.06349998 -0.01477152 -0.4965353 0.06349998 -0.01650995 -0.4960494 0.06349998 -0.01289856 -0.4926159 0.06349998 0.01337283 -0.4920806 0.06349998 -0.01378214 -0.4917981 0.06349998 -0.01748919 -0.4945327 0.06349998 0.01621782 -0.4917981 0.06349998 0.01710134 -0.4926159 0.06349998 0.01266717 -0.4930568 0.06349998 0.01750385 -0.4937511 0.06349998 -0.01249611 -0.4937511 0.06349998 0.01477146 -0.4914647 0.06349998 -0.01522845 -0.4914647 0.06349998 0.01251077 -0.4945327 0.06349998 -0.01278352 -0.4952518 0.06349998 0.01721644 -0.4952518 0.06349998 -0.01662707 -0.4920806 0.06349998 0.01642012 -0.4960575 0.06349998 0.01522845 -0.4965353 0.06349998 -0.01733273 -0.4930568 0.07429683 0.01803374 -0.5813493 0.07429683 -0.01803374 -0.5813493 0.07453829 -0.02081251 -0.588135 0.07453829 0.02081251 -0.588135 0.06685549 0.03610491 -0.586857 0.06600737 0.03779309 -0.5903364 -0.00624293 0.035461 -0.5303646 -0.009115517 0.03257942 -0.5325803 0.01003032 0.02852004 -0.5357022 -0.002043664 0.0370177 -0.5291676 -0.009938538 0.03007519 -0.5345063 -6.07865e-4 0.02125269 -0.5412905 0.002280473 0.02147167 -0.5411223 0.005319118 0.02241885 -0.5403938 0.008582949 0.02502548 -0.5383894 -0.00992906 0.02825373 -0.535907 0.002592802 0.0369153 -0.5292465 -0.008986473 0.02564013 -0.5379168 0.006680071 0.03517323 -0.5305861 -0.006899416 0.02345359 -0.5395982 -0.00432527 0.02199417 -0.5407208 0.009348571 0.03216099 -0.5329024 0.06318497 0.04341101 -0.6252173 -0.05093592 0.04331517 -0.6287867 -0.07235831 0.02543884 -0.6238743 -0.07709956 -5.59713e-5 -0.5548321 -0.07565766 -0.007809519 -0.6237891 -0.0658347 -0.0379309 -0.6381978 -0.05093592 -0.03697431 -0.6441536 -0.05093592 -0.03140038 -0.6510134 -0.05093592 -0.02687144 -0.6550127 -0.05090832 -0.01966041 -0.6596172 -0.05093592 -0.01406347 -0.6618586 -0.05093592 8.8485e-4 -0.6642156 -0.05093592 0.01934117 -0.6597176 -0.05093592 0.02833873 -0.6539035 -0.05093592 0.03561407 -0.6460921 -0.02799999 0 -0.581 -0.02799999 0.009333252 -0.5821333 -0.02799999 0.01812416 -0.5854672 -0.02799999 0.02586174 -0.5908081 -0.02799999 0.03209632 -0.5978455 -0.02799999 0.03646558 -0.6061704 -0.02799999 0.0387156 -0.6152991 -0.02799999 0.0387156 -0.6247009 -0.02799999 0.03646558 -0.6338296 -0.02799999 0.03209632 -0.6421545 -0.02799999 0.02586174 -0.6491919 -0.02799999 0.01812416 -0.6545328 -0.02799999 0.009333252 -0.6578667 -0.02799999 0 -0.659 -0.02775567 -0.009330093 -0.6578667 -0.02752554 -0.01811796 -0.6545328 -0.027323 -0.02585291 -0.6491919 -0.02715981 -0.03208535 -0.6421545 -0.02704542 -0.03645312 -0.6338296 -0.02698653 -0.03870236 -0.6247009 -0.02698653 -0.03870236 -0.6152991 -0.02704542 -0.03645312 -0.6061704 -0.02715981 -0.03208535 -0.5978455 -0.027323 -0.02585291 -0.5908081 -0.02752554 -0.01811796 -0.5854672 -0.02775567 -0.009330093 -0.5821333 -0.009763836 -0.03010439 -0.5400918 -0.009798169 -0.03376418 -0.5370208 0 -0.03965008 -0.5320819 0.003613114 -0.039186 -0.5324712 -0.008229792 -0.0363413 -0.5348583 -0.006631195 -0.0377236 -0.5336985 0.007530272 -0.0371108 -0.5342127 -0.004647195 -0.03877264 -0.5328182 -0.002393126 -0.03942751 -0.5322687 0.00976324 -0.03387659 -0.5369265 0.009927034 -0.03106629 -0.5392846 0.009350121 -0.02927321 -0.5407892 0.008229792 -0.02763801 -0.5421613 0.006631195 -0.02625572 -0.5433211 0.004647195 -0.02520668 -0.5442014 0.002393126 -0.0245518 -0.5447509 0 -0.02432924 -0.5449377 -0.00361371 -0.02479338 -0.5445482 -0.007531464 -0.02686959 -0.5428061 0.05499994 0.01453876 -0.5816643 0.05499994 0.004941999 -0.5792989 0.05499994 -0.004941999 -0.5792989 0.05499994 -0.01453876 -0.5816643 0.05499994 -0.04099994 -0.62 0.05499994 -0.03980857 -0.6298119 0.05499994 -0.02329063 -0.5862577 0.05499994 -0.03630369 -0.6390536 0.05499994 -0.03068894 -0.592812 0.05499994 -0.03068894 -0.647188 0.05499994 -0.03630369 -0.6009464 0.05499994 -0.02329063 -0.6537423 0.05499994 -0.03980857 -0.6101881 0.05499994 -0.01453876 -0.6583357 0.05499994 -0.004941999 -0.6607011 0.05499994 0.004941999 -0.6607011 0.05499994 0.01453876 -0.6583357 0.05499994 0.02329063 -0.6537423 0.05499994 0.03068894 -0.647188 0.05499994 0.03630369 -0.6390536 0.05499994 0.03980857 -0.6298119 0.05499994 0.04099994 -0.62 0.05499994 0.03980857 -0.6101881 0.05499994 0.03630369 -0.6009464 0.05499994 0.03068894 -0.592812 0.05499994 0.02329063 -0.5862577 0.06323313 0.04331517 -0.6287867 0.06710207 0.03561407 -0.6460921 0.0678333 0.03420764 -0.6475867 0.06765478 0.02797037 -0.6541758 0.06488513 0.01934117 -0.6597176 0.06257706 8.8485e-4 -0.6642156 0.0637865 -0.01406347 -0.6618586 0.06495851 -0.01973366 -0.6595746 0.06762224 -0.0275827 -0.6544205 0.06758433 -0.03140038 -0.6510134 0.06784152 -0.03419446 -0.647558 0.0664187 -0.03697431 -0.6441536 0.06339842 -0.04298609 -0.6304566 0.07565045 -0.01859736 -0.6192568 0.05349999 -0.01651 -0.4919507 0.05349999 -0.01477146 -0.4914647 0.05349999 -0.01249611 -0.494249 0.05349999 -0.01289856 -0.495384 0.05349999 -0.01337283 -0.4920806 0.05349999 -0.0137822 -0.4962019 0.05349999 -0.01266717 -0.4930568 0.05349999 -0.01522845 -0.4965353 0.05349999 -0.01662707 -0.4959194 0.05349999 -0.01745164 -0.4946851 0.05349999 -0.01737153 -0.4931591 0.05349999 0.01348996 -0.4919507 0.05349999 0.01522845 -0.4914647 0.05349999 0.01750385 -0.4942489 0.05349999 0.0171014 -0.495384 0.05349999 0.01662707 -0.4920806 0.05349999 0.01621776 -0.4962019 0.05349999 0.01733273 -0.4930568 0.05349999 0.01477152 -0.4965353 0.05349999 0.01337289 -0.4959194 0.05349999 0.01254832 -0.4946851 0.05349999 0.01262843 -0.4931591 0.07565265 0.01859188 -0.6192606 -0.009927034 0.03291302 -0.537735 -0.009927034 0.03106629 -0.5392846 -0.009350121 0.02927321 -0.5407892 0 0.02432924 -0.5449377 -0.008229792 0.02763801 -0.5421613 0.002393126 0.0245518 -0.5447509 0.004647195 0.02520668 -0.5442014 -0.006631195 0.02625572 -0.5433211 0.006631195 0.02625572 -0.5433211 -0.003512322 0.02476769 -0.54457 0.008229792 0.02763801 -0.5421613 0.009350121 0.02927321 -0.5407892 0.009927034 0.03106629 -0.5392846 0.00976324 0.03387653 -0.5369265 0.007530212 0.0371108 -0.5342128 0.003603041 0.03919261 -0.5324659 -0.001135408 0.03965353 -0.5320791 -0.004647195 0.03877264 -0.5328182 -0.006631195 0.0377236 -0.5336985 -0.008229792 0.0363413 -0.5348583 -0.009350121 0.03470605 -0.5362304 -0.06584864 0.03963875 -0.6340666 -0.07535189 0.0180583 -0.555065 -0.07236194 -0.01885205 -0.6375052 -0.06583636 -0.03267484 -0.6464755 -0.06583899 -0.02550309 -0.6534597 -0.06580966 -0.00900191 -0.661141 -0.06580364 0.009195387 -0.6611225 -0.06582605 0.02236998 -0.6556495 -0.06586569 0.03276199 -0.6463728 -0.02799999 0.006898105 -0.5897772 -0.02799999 0 -0.589 -0.02799999 0.01345038 -0.59207 -0.02799999 0.01932817 -0.5957632 -0.02799999 0.02423673 -0.6006718 -0.02799999 0.02793002 -0.6065496 -0.02799999 0.03022271 -0.6131019 -0.02799999 0.03099995 -0.62 -0.02799999 0.006898105 -0.6502228 -0.02799999 0 -0.651 -0.02799999 0.03022271 -0.6268981 -0.02799999 0.01345038 -0.64793 -0.02799999 0.02793002 -0.6334504 -0.02799999 0.01932817 -0.6442368 -0.02799999 0.02423673 -0.6393282 -0.02787154 -0.004904747 -0.5893905 -0.02774631 -0.009685993 -0.5905521 -0.02757352 -0.01628488 -0.593622 -0.02742427 -0.02198618 -0.5981458 -0.02730667 -0.0264756 -0.6038742 -0.02722734 -0.02950572 -0.6104915 -0.02719056 -0.03090947 -0.6176329 -0.02781069 -0.007227718 -0.6501457 -0.02719843 -0.03060948 -0.6249048 -0.02763187 -0.01405704 -0.6476297 -0.02725046 -0.02862232 -0.6319063 -0.02747333 -0.02011156 -0.6435908 -0.0273438 -0.02505755 -0.6382515 0.05499994 -0.01329767 -0.6550631 0.05499994 -0.004520118 -0.6572266 0.05499994 0.03749996 -0.62 0.05499994 0.03641027 -0.6110257 0.05499994 -0.02806913 -0.5951329 0.05499994 -0.0213024 -0.5891381 0.05499994 -0.03320455 -0.6025729 0.05499994 0.03641027 -0.6289743 0.05499994 0.004520118 -0.6572266 0.05499994 -0.01329767 -0.5849369 0.05499994 -0.03641027 -0.6110257 0.05499994 -0.004520118 -0.5827734 0.05499994 0.03320455 -0.6374271 0.05499994 0.01329767 -0.6550631 0.05499994 -0.03749996 -0.62 0.05499994 0.004520118 -0.5827734 0.05499994 0.02806913 -0.6448671 0.05499994 0.0213024 -0.6508619 0.05499994 -0.03641027 -0.6289743 0.05499994 0.01329767 -0.5849369 0.05499994 -0.03320455 -0.6374271 0.05499994 0.0213024 -0.5891381 0.05499994 -0.02806913 -0.6448671 0.05499994 0.02806913 -0.5951329 0.05499994 -0.0213024 -0.6508619 0.05499994 0.03320455 -0.6025729 0.07036525 0.02263444 -0.6489655 0.07035756 -0.02261835 -0.6490159 0.07567161 -0.01293885 -0.6289625 0.07567161 0.01293885 -0.6289625 -0.07441836 0.01427441 -0.6297537 -0.07236832 -0.005720973 -0.6450695 -0.02499997 -0.003736615 -0.589226 -0.02499997 0.003736615 -0.589226 -0.02499997 0.0109927 -0.5910145 -0.02499997 0.03099995 -0.62 -0.02499997 0.03009915 -0.6274188 -0.02499997 0.01761001 -0.5944875 -0.02499997 0.02744913 -0.6344064 -0.02499997 0.02320379 -0.5994432 -0.02499997 0.02320379 -0.6405568 -0.02499997 0.02744913 -0.6055936 -0.02499997 0.01761001 -0.6455125 -0.02499997 0.03009915 -0.6125812 -0.02499997 0.0109927 -0.6489855 -0.02499997 0.003736615 -0.650774 -0.02499997 -0.003736615 -0.650774 -0.02499997 -0.0109927 -0.6489855 -0.02499997 -0.01761001 -0.6455125 -0.02499997 -0.02320379 -0.6405568 -0.02499997 -0.02744913 -0.6344064 -0.02499997 -0.03009915 -0.6274188 -0.02499997 -0.03099995 -0.62 -0.02499997 -0.03009915 -0.6125812 -0.02499997 -0.02744913 -0.6055936 -0.02499997 -0.02320379 -0.5994432 -0.02499997 -0.01761001 -0.5944875 -0.02499997 -0.0109927 -0.5910145 0.05299997 0.01329767 -0.5849369 0.05299997 0.004520118 -0.5827734 0.05299997 0.03749996 -0.62 0.05299997 0.0213024 -0.5891381 0.05299997 0.02806913 -0.5951329 0.05299997 0.03641027 -0.6289743 0.05299997 0.03320455 -0.6025729 0.05299997 0.03320455 -0.6374271 0.05299997 0.03641027 -0.6110257 0.05299997 0.02806913 -0.6448671 0.05299997 0.0213024 -0.6508619 0.05299997 0.01329767 -0.6550631 0.05299997 0.004520118 -0.6572266 0.05299997 -0.004520118 -0.6572266 0.05299997 -0.01329767 -0.6550631 0.05299997 -0.0213024 -0.6508619 0.05299997 -0.02806913 -0.6448671 0.05299997 -0.03320455 -0.6374271 0.05299997 -0.03641027 -0.6289743 0.05299997 -0.03749996 -0.62 0.05299997 -0.03641027 -0.6110257 0.05299997 -0.03320455 -0.6025729 0.05299997 -0.02806913 -0.5951329 0.05299997 -0.0213024 -0.5891381 0.05299997 -0.01329767 -0.5849369 0.05299997 -0.004520118 -0.5827734 -0.06953155 0.01238459 -0.651544 + + + + + + + + + + 0 0 1 -9.30866e-5 0 1 -9.30874e-5 0 1 -6.22841e-5 0 1 -4.73167e-6 0 1 -2.32726e-5 0 1 -6.22852e-5 0 1 -6.29731e-6 0 1 6.47347e-6 0 1 -1.16783e-5 0 1 6.22846e-5 0 1 1.5571e-5 0 1 -2.0968e-6 0 1 3.78532e-5 0 1 4.6543e-5 0 1 -3.18286e-6 0 1 1.86168e-4 0 1 -2.53515e-6 0 1 4.73169e-6 0 1 8.61021e-6 0 1 -7.82847e-6 0 1 -3.11425e-5 0 1 1.25947e-5 0 1 3.18354e-6 0 1 -0.6270008 -0.7742825 -0.08577078 -0.6231661 -0.777304 -0.08638656 -0.5487545 -0.8314993 -0.08647221 -0.5426387 -0.8355907 -0.08562463 -0.4587385 -0.8843315 -0.08670139 -0.4523171 -0.8877223 -0.08578068 -0.3570497 -0.9301461 -0.08569622 -0.351902 -0.9320424 -0.08638322 -0.2642441 -0.9605792 -0.08638781 -0.2578691 -0.9623783 -0.08562427 -0.1624588 -0.9828984 -0.08670562 -0.155855 -0.9840415 -0.08585846 -0.04504925 -0.9952152 -0.0867027 -0.05214428 -0.994946 -0.08581137 0.05902934 -0.9945086 -0.08641904 0.05214554 -0.994962 -0.08562487 0.1483542 -0.9851442 -0.08649826 0.1558585 -0.9840613 -0.08562481 0.2489161 -0.9646378 -0.08668762 0.2578694 -0.9623782 -0.08562475 0.3495439 -0.9329003 -0.08669668 0.3570497 -0.9301461 -0.08569622 0.4523171 -0.8877223 -0.08578062 0.4587389 -0.8843312 -0.08670145 0.5426377 -0.8355914 -0.08562463 0.5507062 -0.8301799 -0.08674275 0.6270089 -0.7742921 -0.08562558 0.6321195 -0.7700405 -0.08638739 0.7013846 -0.7075299 -0.08637839 0.7044968 -0.704498 -0.08583122 0.7742763 -0.6269965 -0.08585834 0.7768186 -0.6237722 -0.08637738 0.8319117 -0.5481424 -0.08638769 0.8355911 -0.542638 -0.08562451 0.8829298 -0.4614344 -0.08668065 0.8877432 -0.4523268 -0.08551323 0.9272339 -0.3642953 -0.08675438 0.9301406 -0.3570462 -0.08577084 0.9623662 -0.2578659 -0.08577114 0.9641698 -0.2507182 -0.0867002 0.9840613 -0.1558591 -0.08562469 0.9853729 -0.1467166 -0.08668768 0.994962 -0.05214613 -0.08562439 0.9952583 -0.04446595 -0.0865097 0.9949494 0.05214536 -0.08577072 0.9951732 0.04634428 -0.08650231 0.9840487 0.1558573 -0.08577078 0.9832338 0.1605936 -0.08637702 0.9636485 0.2528074 -0.08642917 0.9623661 0.2578658 -0.08577114 0.9301399 0.3570482 -0.08577066 0.9272347 0.3642931 -0.0867545 0.8877427 0.4523279 -0.08551317 0.8841306 0.4591837 -0.08639222 0.838159 0.5385425 -0.0863806 0.8355806 0.5426312 -0.08577102 0.7742823 0.6270012 -0.0857712 0.7705584 0.631472 -0.08650469 0.7082534 0.7006453 -0.0864492 0.7045017 0.7045004 -0.08577108 0.6270008 0.7742825 -0.08577078 0.6231661 0.777304 -0.08638656 0.5487549 0.8314991 -0.08647233 0.542638 0.8355912 -0.08562457 0.4587396 0.8843307 -0.08670157 0.4523171 0.8877224 -0.0857805 0.3570495 0.9301461 -0.08569616 0.3519017 0.9320424 -0.08638358 0.2642443 0.960579 -0.08638787 0.2578691 0.9623783 -0.08562427 0.1645055 0.9825592 -0.08669114 0.1558574 0.9840562 -0.08568412 0.05214363 0.9949356 -0.08593147 0.05902105 0.9944759 -0.08680021 -0.05214363 0.9949356 -0.08593147 -0.05588138 0.9946918 -0.0864039 -0.1483511 0.9851447 -0.08649808 -0.1558586 0.9840613 -0.08562487 -0.248915 0.9646382 -0.08668786 -0.2578694 0.9623782 -0.08562475 -0.3495439 0.9329003 -0.08669668 -0.3570497 0.9301461 -0.08569622 -0.4523171 0.8877223 -0.08578062 -0.4587389 0.8843312 -0.08670145 -0.5426377 0.8355914 -0.08562463 -0.550705 0.8301807 -0.08674263 -0.6270101 0.7742911 -0.08562564 -0.632119 0.7700409 -0.08638763 -0.7013837 0.7075309 -0.08637833 -0.7044968 0.704498 -0.08583128 -0.774276 0.6269968 -0.08585834 -0.77682 0.6237705 -0.08637738 -0.8319113 0.5481431 -0.08638751 -0.8355911 0.542638 -0.08562451 -0.8829298 0.4614344 -0.08668065 -0.8877432 0.4523268 -0.08551323 -0.9272339 0.3642953 -0.08675438 -0.9301406 0.3570462 -0.08577084 -0.9623662 0.2578659 -0.08577114 -0.9641697 0.2507185 -0.08670026 -0.9840611 0.1558593 -0.08562475 -0.9850099 0.1493076 -0.08638733 -0.9945462 0.05844134 -0.08638596 -0.9949584 0.05214506 -0.08566772 -0.9952706 -0.04349124 -0.08686155 -0.9949494 -0.05214536 -0.08577078 -0.9840492 -0.1558548 -0.08577066 -0.9832332 -0.1605973 -0.08637702 -0.9636486 -0.2528072 -0.08642917 -0.9623661 -0.2578658 -0.08577114 -0.9301399 -0.3570482 -0.08577066 -0.9272347 -0.3642931 -0.0867545 -0.8877427 -0.4523279 -0.08551317 -0.8841306 -0.4591837 -0.08639222 -0.838159 -0.5385425 -0.0863806 -0.8355806 -0.5426312 -0.08577102 -0.7742823 -0.6270012 -0.0857712 -0.7705584 -0.631472 -0.08650469 -0.7082534 -0.7006453 -0.0864492 -0.7045017 -0.7045004 -0.08577108 -0.9995393 0 -0.03035229 -0.9982628 0.05866348 -0.005481302 -0.9887064 0.1498658 1.97372e-4 -0.9705727 0.2392237 -0.02758407 -0.9307422 0.3656668 0.002605974 0.05924302 0.9982373 -0.003553807 -0.9676269 0.2516188 -0.0196523 -0.8851683 0.4645731 -0.02548044 -0.8350303 0.5502032 9.8895e-4 0.1204804 0.9922453 -0.03055679 -0.7797119 0.626091 -0.007733285 -0.8859496 0.4630154 -0.02664703 0.2652372 0.9641832 5.01916e-4 0.3531085 0.9352415 -0.02525222 0.1651253 0.9862357 -0.008540153 -0.7040081 0.7101821 -0.003744423 -0.6344959 0.7729257 -8.45116e-4 -0.7481347 0.662788 -0.03172802 0.354483 0.9346939 -0.02625495 0.5507363 0.8345024 -0.01718521 0.4604732 0.8876693 0.002758622 -0.460473 0.8876694 0.002758145 -0.5526992 0.8331943 -0.01763314 -0.5678315 0.8226484 -0.02858555 0.567829 0.822642 -0.02881443 -0.3544835 0.9346936 -0.02625459 0.7108998 0.7032678 -0.005997359 -0.1488977 0.9887499 -0.01425522 0.625505 0.7802164 -0.002438604 -0.2498537 0.9682812 0.002169251 -0.3507677 0.9361664 -0.0235489 -0.1204844 0.9922805 -0.02937811 -0.05609065 0.9984194 -0.003554463 0.7481812 0.6628295 -0.02970039 0.8413031 0.5405636 1.04618e-4 0.8870906 0.4607237 -0.02835971 0.7734166 0.6338095 -0.0106067 0.9670881 0.2537125 -0.01925301 0.930741 0.36567 0.002606034 0.885169 0.4645715 -0.02548056 0.9988838 0.04652291 -0.008183658 0.9869225 0.1611931 -0.001043975 0.9705605 0.2392212 -0.02802681 0.9995571 0 -0.02975988 0.9890956 -0.1472717 9.97859e-4 0.9989624 -0.04463309 -0.009061455 0.9705725 -0.2392241 -0.02758401 0.9307422 -0.3656668 0.002605974 0.9676272 -0.2516177 -0.0196523 0.8350288 -0.5502054 9.89109e-4 0.7797114 -0.6260914 -0.007733166 0.8859496 -0.4630154 -0.02664703 0.8851683 -0.4645731 -0.02548044 0.7040081 -0.7101822 -0.003744482 0.6344955 -0.7729262 -8.45441e-4 0.7481345 -0.6627883 -0.03172779 0.460473 -0.8876694 0.002758145 0.5526997 -0.833194 -0.01763284 0.5678322 -0.8226479 -0.02858537 0.1489008 -0.9887494 -0.01425367 0.2498536 -0.9682813 0.002168715 0.3507677 -0.9361664 -0.0235489 0.3544835 -0.9346936 -0.02625459 -0.04521566 -0.9989767 -0.001095235 0.1204844 -0.9922804 -0.02937859 0.05924773 -0.9982317 -0.004818439 -0.1204771 -0.9922204 -0.03136992 -0.265237 -0.9641832 5.01916e-4 -0.3531087 -0.9352415 -0.02525347 -0.1630701 -0.986576 -0.008722603 -0.3544831 -0.9346939 -0.02625447 -0.5507346 -0.8345036 -0.01718515 -0.4604731 -0.8876695 0.002758145 -0.567829 -0.822642 -0.02881443 -0.7108998 -0.7032678 -0.005997359 -0.625505 -0.7802164 -0.002438604 -0.7481812 -0.6628295 -0.02970039 -0.8413031 -0.5405636 1.04618e-4 -0.8870906 -0.4607237 -0.02835971 -0.7734166 -0.6338095 -0.0106067 -0.9670883 -0.2537115 -0.01925301 -0.930741 -0.36567 0.002606034 -0.885169 -0.4645715 -0.02548056 -0.9705605 -0.2392212 -0.02802681 -0.9990117 -0.043657 -0.008360028 -0.9869217 -0.1611967 -0.001044452 -7.55652e-6 0 -1 -1.58195e-6 0 -1 3.16391e-6 0 -1 0 0 -1 -3.1639e-6 0 -1 3.77826e-6 0 -1 1.58195e-6 0 -1 3.16391e-6 0 -1 7.55651e-6 0 -1 -7.55653e-6 0 -1 5.66739e-6 0 -1 -6.32781e-6 0 -1 6.32781e-6 0 -1 6.32782e-6 0 -1 1.88913e-6 0 -1 -7.90977e-6 0 -1 -3.77825e-6 0 -1 1.58195e-6 0 -1 -3.77826e-6 0 -1 -1.88913e-6 0 -1 6.32781e-6 0 -1 9.44565e-6 0 -1 -1.88913e-6 0 -1 4.72281e-7 0 -1 3.16391e-6 0 -1 -3.16391e-6 0 -1 3.95488e-7 0 -1 -1.58196e-6 0 -1 -0.970942 0.2393149 0 -1 0 0 -0.8854559 0.4647236 0 -0.9709419 0.2393155 0 0.1205373 0.9927088 0 -0.7485107 0.6631227 0 0.1205369 0.9927089 0 -0.5680645 0.8229841 0 -0.7485102 0.6631233 0 0.3546038 0.9350167 0 0.3546046 0.9350165 0 -0.3546038 0.9350167 0 -0.5680664 0.8229828 0 0.5680645 0.8229841 0 0.5680664 0.8229828 0 -0.1205369 0.9927089 0 -0.3546046 0.9350165 0 0.7485107 0.6631227 0 -0.1205373 0.9927088 0 0.7485102 0.6631233 0 0.8854559 0.4647236 0 0.970942 0.2393149 0 0.9709419 0.2393155 0 1 0 0 0.9709419 -0.2393155 0 0.970942 -0.2393149 0 0.8854559 -0.4647236 0 0.7485102 -0.6631233 0 0.7485107 -0.6631227 0 0.5680665 -0.8229827 0 0.5680643 -0.8229843 0 0.3546045 -0.9350164 0 0.3546039 -0.9350166 0 0.1205373 -0.9927088 0 0.1205369 -0.9927089 0 -0.1205369 -0.9927089 0 -0.1205373 -0.9927088 0 -0.3546039 -0.9350166 0 -0.3546045 -0.9350164 0 -0.5680643 -0.8229843 0 -0.5680665 -0.8229827 0 -0.7485102 -0.6631233 0 -0.7485107 -0.6631227 0 -0.8854559 -0.4647236 0 -0.9709419 -0.2393155 0 -0.970942 -0.2393149 0 -6.57658e-6 0 1 3.28828e-6 0 1 6.57657e-6 0 1 -6.57657e-6 0 1 -3.28829e-6 0 1 3.61497e-6 0 1 -3.28829e-6 0 1 -7.22993e-6 0 1 -3.61497e-6 0 1 6.57658e-6 0 1 -3.28829e-6 0 1 -3.61498e-6 0 1 -3.28829e-6 0 1 3.61497e-6 0 1 3.28829e-6 0 1 -6.57657e-6 0 1 3.28829e-6 0 1 -3.61497e-6 0 1 -7.22994e-6 0 1 -3.28829e-6 0 1 7.22995e-6 0 1 -3.61497e-6 0 1 3.28829e-6 0 1 6.57657e-6 0 1 3.61497e-6 0 1 0.6604988 0.7455505 0.08885943 0.562881 0.8216795 -0.08948689 0.3490626 0.932821 -0.08944523 0.4628838 0.8819579 0.08881974 -0.994486 -0.1048701 0 0.1148036 0.9893579 -0.08939301 0.2383699 0.9671087 0.08877247 -0.126177 0.9879773 -0.08933305 0 0.996057 0.08871608 -0.3597734 0.9287604 -0.08926075 -0.2383725 0.9671195 0.08864814 -0.9398192 -0.3390048 0.04261165 -0.967503 -0.2527001 -0.008981645 -0.5723105 0.8151734 -0.0891807 -0.4628964 0.8819761 0.08857244 -0.9922057 -0.1204763 0.03183066 -0.8639677 -0.4323269 0.2581734 -0.8456376 -0.5337085 0.007252931 -0.9329773 -0.3538344 0.06599056 -0.8766831 -0.4779818 -0.05440866 -0.751352 -0.6538602 -0.08908963 -0.8197643 -0.5658387 0.08839333 -0.8669601 0.4983777 0 -0.751352 0.6538602 -0.08908963 -0.5723105 -0.8151734 -0.0891807 -0.6605208 0.7455749 0.08848983 -0.6605208 -0.7455749 0.08848983 -0.3597734 -0.9287604 -0.08926075 -0.4628964 -0.8819761 0.08857244 -0.9298816 0.3666521 0.02977478 -0.8652337 0.5009926 -0.01942503 -0.126177 -0.9879773 -0.08933305 -0.8197643 0.5658387 0.08839315 -0.2383725 -0.9671195 0.08864814 -0.9735705 0.2270315 -0.02484542 0 -0.996057 0.08871608 -0.9337362 0.3541183 0.0523175 0.1148036 -0.9893579 -0.08939301 -0.9969577 0.07794511 0 -0.9906786 0.1202911 0.06392401 0.2383699 -0.9671087 0.08877247 0.3490626 -0.932821 -0.08944523 0.4628838 -0.8819579 0.08881974 0.562881 -0.8216795 -0.08948689 0.6604987 -0.7455504 0.08885979 0.7437523 -0.6624342 -0.0895189 0.819728 -0.5658141 0.08888512 0.8810773 -0.4644186 -0.08954423 0.9313136 -0.3532006 0.0889064 0.9668284 -0.2392117 -0.08955889 0.9887769 -0.1200603 0.0889157 0.9959812 0 -0.08956331 0.9887769 0.1200603 0.0889157 0.9668284 0.2392117 -0.08955889 0.9313136 0.3532006 0.08890628 0.8810773 0.4644186 -0.08954423 0.819728 0.5658141 0.08888512 0.7437523 0.6624342 -0.0895189 0.01585608 -0.003479838 0.9998683 0.00758928 -1.27298e-4 0.9999713 0.006504237 0.001870691 0.9999772 0.006504595 0.001871883 0.9999771 0.001969158 9.02662e-4 0.9999977 0.002308666 6.67608e-4 0.9999971 0.002543866 0.001124024 0.9999961 -0.003883481 -0.001383423 0.9999916 -0.003880143 -0.001381933 0.9999915 -0.003866314 -0.001394093 0.9999916 -0.003862917 -0.001379907 0.9999917 -0.004732847 -0.002376317 0.9999861 6.62691e-4 -2.7824e-4 0.9999998 -1 0 2.10438e-4 -0.9999997 -4.35079e-4 8.31056e-4 -1 -5.61125e-6 -4.84564e-5 -1 2.0259e-5 2.84943e-6 -1 -2.27631e-5 -1.88404e-4 -7.36193e-6 0 1 -1.89406e-5 0 1 -1.21832e-6 0 1 1.46731e-5 0 1 4.7275e-6 0 1 5.37533e-6 0 1 9.59056e-6 0 1 -3.17205e-6 0 1 -5.65498e-7 0 1 -6.83438e-6 0 1 1.09108e-5 0 1 -3.45773e-6 0 1 6.28292e-6 0 1 2.01607e-5 0 1 3.23404e-6 0 1 -3.6799e-5 0 1 3.27293e-5 0 1 -2.12031e-5 0 1 2.52527e-5 0 1 -7.11107e-5 0 1 2.03904e-5 0 1 4.97197e-5 0 1 -7.43358e-5 0 1 -1.70841e-5 0 1 6.11385e-6 0 1 3.72118e-5 0 1 -2.98991e-5 0 1 -9.57168e-6 0 1 4.46236e-5 0 1 -0.9998241 0.008011996 -0.01696217 -0.004987716 -5.19986e-4 0.9999874 -0.04421931 0.003274381 0.9990165 0 0.0243957 0.9997025 -0.02493721 0.02628296 0.9993435 -0.9641461 0.1236495 0.2348048 -0.9673207 -0.1014724 0.2323665 -0.1092032 -0.09309709 0.9896503 -0.1730604 -0.9019774 0.3955843 -0.1731097 -0.9019671 0.3955863 0.002148807 -0.9898185 -0.1423197 2.76959e-4 -0.9908677 -0.1348383 7.22471e-4 -0.9908025 -0.1353139 0 -0.9907721 -0.1355392 -5.19056e-7 -0.990772 -0.1355395 0 -0.9907722 -0.1355381 0 -0.990772 -0.1355394 -4.14323e-6 -0.9907719 -0.1355404 -2.17118e-6 -0.990772 -0.1355388 4.06463e-6 -0.9908323 -0.1350973 0.005694687 -0.03896677 0.9992243 -4.0337e-5 0.002149462 0.9999977 -0.7819888 -0.6232861 -0.002851724 -0.781836 -0.6234841 0 -0.06492894 -0.204629 0.9766838 -0.1195966 -0.4175976 0.9007269 -0.5878142 -0.8089961 0 -0.5877901 -0.8090136 0 -0.5891544 -0.8079363 0.01167422 -0.351353 -0.9361515 0.01309037 -0.3497345 -0.9367788 -0.01145893 -0.3513751 -0.9362348 0 -0.3513755 -0.9362347 0 -0.0896393 -0.9959744 0 -0.08963876 -0.9959744 0 0.1769804 -0.9842144 0 0.17698 -0.9842145 0 0.4338831 -0.9009693 0 0.4338833 -0.9009692 0 0.5877874 -0.8090155 0 0.5877859 -0.8090166 0 0.7116481 -0.7025361 0 0.713029 -0.7011335 -0.00124824 0.7156396 -0.6984698 0 0.7130254 -0.7011352 0.002070546 0.9005006 -0.4348549 0 0.9005046 -0.4348466 2.48415e-4 0.9003426 -0.4351818 1.61642e-4 0.9005039 -0.4348478 0 0.9510602 -0.3090057 0 0.9510517 -0.3090318 0 1 0 0 0.9999999 0 5.37777e-4 0.9999998 0 7.07006e-4 0.9999999 -1.91562e-4 5.57274e-4 0.9999998 1.03448e-6 7.07003e-4 0.9195359 0.393006 0 0.9195247 0.3930322 0 0.9004943 0.4348679 0 0.9005041 0.4348475 3.26657e-4 0.900292 0.4352865 1.96724e-4 0.9005039 0.434848 0 0.7130294 0.701133 -0.001325011 0.7116003 0.7025845 0 0.7181212 0.6959169 0.001308023 0.713028 0.7011327 0.00207585 0.433884 0.9009688 0 0.4397397 0.8980983 -0.00696814 0.1785573 0.9839296 0 0.1785573 0.9839295 0 0.04486471 0.9989932 0 0.04486459 0.9989931 0 -0.1349424 0.9908535 0 -0.1349411 0.9908537 0 -0.3513757 0.9362345 0 -0.3513748 0.936235 0 -0.5129118 0.8584414 6.23389e-6 -0.5128993 0.8584488 0 -0.5129193 0.8584368 0 -0.5128964 0.8584505 0 -0.5129002 0.8584483 -6.10122e-7 -0.5128994 0.8584488 0 -0.6595582 0.7516536 0 -0.7818369 0.6234831 0 -0.7818276 0.6234949 -1.47148e-5 -0.7621976 0.6466112 0.03080445 -0.4003388 0.911216 -0.09702736 -0.4003137 0.9112262 -0.09703409 -0.4003174 0.9112248 -0.09703421 -0.4003174 0.9112246 -0.09703433 -0.4003159 0.9112253 -0.09703445 -0.4004259 0.9112796 -0.09606629 0.001756429 0.9898231 -0.1422927 1.16696e-4 0.9908321 -0.1350995 4.07974e-4 0.9907892 -0.1354125 -7.81191e-7 0.990772 -0.1355392 -9.77703e-7 0.9907719 -0.1355397 0.002692103 0.9909623 -0.1341134 0 0.989961 -0.1413406 -0.009805262 0.9908151 -0.1348684 -0.9999999 -5.26571e-4 2.53382e-4 -0.9999923 0.003545701 -0.001706421 -0.9999868 -0.00227189 0.004613876 -0.07565766 0.3404743 0.937205 -0.9301693 0.2948389 0.2187582 -0.9563935 0.211071 0.2018922 -0.9806639 -4.73066e-4 0.1956992 -0.9457814 -0.2496706 0.2077549 -0.9758873 -0.06492155 0.2083969 -0.9210217 -0.3042054 0.2432659 -0.351996 -0.9359959 -0.003225505 -0.4023979 -0.7180227 0.5679079 -0.4952901 -0.8687049 0.006293654 -0.4952898 -0.8687051 0.006293654 -0.8618434 -0.5058088 0.03719818 -0.7711164 -0.6366801 0.004266619 -7.08025e-5 -0.9996949 -0.02470028 -3.92966e-4 -0.9997074 -0.02418804 6.99213e-7 -0.9996908 -0.02486968 -9.17022e-4 -0.9996943 -0.0247091 -7.4719e-4 -0.9996991 -0.02452003 0.001341402 -0.9996681 -0.02573025 -0.001516878 -0.9996625 -0.02593886 0 -0.9996908 -0.02486747 0.001950442 -0.9996748 -0.02542781 0 -0.9996908 -0.02486801 -0.05152654 -0.9615385 -0.2697941 -0.05278825 -0.961889 -0.2682967 -0.06116485 -0.9611572 -0.2691391 -0.1078433 -0.9629085 -0.2473397 -0.09487432 -0.9614686 -0.2580251 -0.09936892 -0.9631863 -0.2497961 -0.2162966 -0.9564177 -0.1961655 -0.2141543 -0.95634 -0.1988767 -0.2153478 -0.9565781 -0.1964272 -0.2105619 -0.9574422 -0.1974036 -0.2092672 -0.9577057 -0.1975021 -0.2139425 -0.9562988 -0.1993018 -0.2139211 -0.9563745 -0.1989614 -0.2138307 -0.9563645 -0.1991071 -0.2139769 -0.9563397 -0.1990692 -0.3251982 -0.9358637 -0.135666 -0.3122444 -0.9382457 -0.148992 -0.3193976 -0.9475504 -0.01155495 -0.4003148 -0.9112255 -0.09703683 -0.400038 -0.911671 -0.0939452 -0.4057332 -0.9088997 -0.09634274 -0.005674064 -0.01290225 0.9999008 0.1351965 0.1521514 0.9790669 -0.3202893 -0.8509289 -0.4163351 -0.3151488 -0.8510231 -0.420049 -0.3205053 -0.8539835 -0.409864 -0.5960474 -0.8029493 0 -0.081236 -0.9026134 -0.4227173 -0.08663761 -0.9029 -0.4210292 0.1625907 -0.8983361 -0.4081134 0.1614967 -0.8981054 -0.4090546 0.3918077 -0.8136048 -0.4295743 0.3998221 -0.8170039 -0.4155084 0.5347893 -0.736077 -0.4149593 0.5422068 -0.7235212 -0.4272338 0.003565013 -0.9904644 -0.1377229 -0.001239001 -0.9906694 -0.136281 7.59727e-5 -0.9907707 -0.1355488 1.30557e-4 -0.9907736 -0.1355279 0.03680831 -0.9904998 -0.1324965 0.7112165 -0.699352 0.07125914 0.7137288 -0.6967764 0.07137238 -3.75104e-5 0.001896679 0.9999982 0.8968909 -0.4329412 0.09027099 0.8623118 -0.4864344 0.1407123 0.8968777 -0.4330899 0.08968663 0.896878 -0.4330889 0.08968734 0.8968715 -0.4331023 0.08968758 0.8968751 -0.4330949 0.08968764 0.8970079 -0.4328515 0.08953559 -1.07734e-4 0.001852571 0.9999983 0.8704607 0.4747136 0.1301745 0.8968773 0.4330905 0.08968764 0.8968777 0.4330899 0.08968663 0.8968968 0.4328895 0.0904594 0.8968715 0.4331023 0.08968758 0.8971793 0.4325366 0.08933931 0.8968751 0.4330952 0.08968764 0.7112165 0.699352 0.07125908 0.7137288 0.6967764 0.07137238 0.003564357 0.9904643 -0.1377237 -0.001239359 0.9906696 -0.1362807 7.59727e-5 0.9907707 -0.1355488 0.002563476 0.990797 -0.1353327 1.30558e-4 0.9907736 -0.1355281 0.5927523 0.6906735 -0.4142645 0.3959544 0.8221517 -0.4090071 0.3889841 0.8148869 -0.42971 0.3961133 0.8221538 -0.4088492 0.3884708 0.8174522 -0.4252792 0.1501975 0.89344 -0.423327 0.1619645 0.89249 -0.4209859 0.04069972 0.9062409 -0.4207981 -0.1288201 0.9001322 -0.4161339 -0.122494 0.8994517 -0.419502 -0.318684 0.8491263 -0.4212185 -0.3186829 0.8491263 -0.4212193 -0.3186744 0.8491299 -0.4212188 -0.659556 0.7516555 0 0 0.2923597 0.9563084 -0.01124489 -5.19951e-4 0.9999366 -0.005717396 0.006517827 0.9999625 -0.00583446 0.006796181 0.99996 -0.4642506 0.7770204 -0.4251007 -0.4659264 0.7783015 -0.4209033 -0.4651815 0.7785772 -0.4212172 -0.5963041 0.6795798 -0.4273089 -0.308947 0.9393473 -0.1489251 -0.30893 0.9393495 -0.1489459 -2.29773e-4 0.9997043 -0.02432191 -2.27418e-4 0.9997004 -0.02447479 6.4568e-7 0.9996907 -0.02486985 -5.31976e-4 0.9996929 -0.02477735 -4.32762e-4 0.9996957 -0.02466619 0.001284599 0.9996691 -0.02569395 -0.001090168 0.9996649 -0.02586483 0 0.9996908 -0.02486747 0.001869261 0.9996756 -0.02540385 0 0.9996908 -0.02486723 -0.8062571 0.5911138 0.02311134 -0.7541556 0.6566764 0.005062401 -0.5423659 0.8401086 0.00753504 -0.5423654 0.8401089 0.007535517 -0.2912517 0.9566124 -0.008090913 -0.2139264 0.9563541 -0.1990537 -0.2129389 0.9566318 -0.198778 -0.2075436 0.9568743 -0.2032662 -0.1016746 0.9624621 -0.2516528 -0.03950393 0.9606081 -0.2750844 -0.05137825 0.9611524 -0.2711945 -0.06623142 0.9624527 -0.2632458 -0.321089 0.8392337 0.4388493 -0.2275465 0.732809 0.6412594 -0.2749635 0.5247915 0.8055985 -0.9116836 0.359676 0.1986615 -0.9727821 0.2085167 0.1010733 -0.9891331 0.02994114 0.1439426 -0.9479475 -0.2845232 0.1429758 -0.9822136 -0.1629282 0.09333163 -0.8939773 -0.3917459 0.2175775 -0.8782793 -0.4540255 0.1499547 -0.8051854 -0.5827586 -0.1098582 -0.9195 -0.3927639 -0.01601386 -0.8686483 -0.4954254 0.002034664 -0.9232951 -0.3836287 -0.01884782 -0.9272184 -0.3713651 0.0485174 0.6525619 -0.483253 -0.5836349 0.6643168 -0.4838568 -0.5697067 0.7658925 -0.4166887 -0.4896727 0.8512259 -0.3335417 -0.4051721 0.7608853 -0.4133105 -0.500228 0.9963244 2.95729e-6 -0.08565998 0.9963242 -4.56313e-7 -0.0856629 0.9963245 -1.79471e-6 -0.08565914 0.9963243 -4.67224e-7 -0.08566224 0.9963243 0 -0.08566313 0.996324 -7.15956e-7 -0.08566451 0.9967228 0.001378655 -0.08088153 0.9963241 0 -0.08566373 0.9963243 0 -0.08566153 0.9963243 1.11019e-6 -0.08566319 0.9963242 -9.12625e-7 -0.08566272 0.9963244 -1.47865e-6 -0.08566051 0.9963243 -4.38023e-7 -0.08566325 0.9963244 -1.43579e-6 -0.08566057 0 -0.9563051 -0.292371 8.09258e-4 -0.9561967 -0.292724 4.24067e-4 -0.9562328 -0.2926069 -0.003561973 -0.956988 -0.2901057 -0.002221286 -0.9552394 -0.2958256 -0.002058386 -0.9569481 -0.2902523 -0.006845355 -0.9550436 -0.2963866 8.57124e-4 -0.9562737 -0.292472 6.13857e-4 -0.9560777 -0.2931128 -6.98952e-5 -0.9563449 -0.2922408 0.00402528 -0.9541567 -0.2992807 8.7191e-5 -0.9872859 0.1589549 -9.98476e-5 -0.9872564 0.1591384 0 -0.987264 0.1590906 0.6946699 -0.5509521 0.4624777 0.6945031 -0.5511257 0.4625214 0.6945561 -0.5511216 0.4624466 0.8036052 -0.4559209 0.3825635 0.6426901 -0.6587201 -0.3911998 0.7256039 -0.6110513 -0.3164104 0.7414373 -0.5921736 -0.3155966 0.8222402 -0.5218029 -0.2272504 0.8239999 -0.518743 -0.2278817 0.8658859 -0.4745544 -0.15824 0.06258535 -0.5316124 0.8446725 -0.4663903 -0.5007809 -0.7291768 -0.4698492 -0.502397 -0.7258369 0.1208704 -0.4834213 0.8670031 0.3328313 -0.5379644 0.774479 0.3154212 -0.5107625 0.7997696 -0.6717463 -0.5105965 -0.5367013 -0.6393325 -0.4992505 -0.5848101 -0.7483173 -0.4897215 -0.4474307 0.624092 -0.5568185 0.5481445 0.5743474 -0.448209 0.6850064 -0.8364593 -0.513994 -0.190121 -0.8351626 -0.5021474 -0.2243916 0.7413024 -0.4683656 0.4807333 -0.8764308 -0.4815245 0.001811504 0.8286533 -0.5084486 0.2341231 0.8303828 -0.4939006 0.2579277 -0.8237735 -0.525651 0.2123396 0.8530027 -0.5207241 -0.03511482 -0.8092161 -0.4613783 0.3637298 0.8713909 -0.4889605 0.03994429 -0.625958 -0.5349457 0.567459 -0.5731335 -0.4689023 0.6720482 0.8365575 -0.4701527 -0.2812968 0.7567539 -0.5248962 -0.3896249 -0.2881515 -0.5472725 0.7857872 -0.3411169 -0.4955875 0.7987692 -0.08434492 -0.4692481 0.8790292 0.6408188 -0.4731599 -0.604542 0.4943695 -0.5227279 -0.6945175 0.3670735 -0.4861294 -0.7930544 0.1515104 -0.510149 -0.8466361 0.1203677 -0.5012575 -0.8568855 -0.07666206 -0.4984969 -0.8634951 -0.1413028 -0.5105701 -0.848146 -0.2658345 -0.4905717 -0.8298623 0.01957309 0.9935486 0.1117057 -0.04964554 -0.9606946 -0.2731326 -0.1433171 -0.9605781 -0.2382226 -0.5272201 -0.7268525 -0.4401413 -0.05184692 -0.9616116 -0.269472 -0.05230742 -0.9616802 -0.2691379 -0.05263251 -0.9617503 -0.2688238 -0.05319321 -0.9619422 -0.2680259 -0.05686283 -0.9635267 -0.2615014 0.09043771 -0.9025939 -0.4208862 0.02358555 -0.9569247 -0.2893767 0.3459605 -0.832008 -0.4336751 0.06858563 -0.9530411 -0.2949724 0.05646711 -0.9541987 -0.2937968 0.06800264 -0.9542806 -0.2910742 0.3242046 -0.9332636 -0.1546306 0.3531828 -0.9210174 -0.1642833 0.3547675 -0.9210938 -0.1603941 0.3559482 -0.9208065 -0.159425 0.5526204 -0.8332213 -0.01878768 0.7367147 -0.6759706 -0.0177589 0.1335991 -0.9469225 -0.2923853 0.1325247 -0.9476667 -0.2904568 -0.5800326 -0.3780351 -0.7215621 -0.5801458 -0.3780028 -0.721488 -0.930054 0 -0.367423 -0.9299945 -6.66986e-5 -0.3675736 -0.9301055 6.45522e-5 -0.3672927 -0.9300238 -3.50356e-7 -0.3674995 -0.9300231 0 -0.367501 -0.9300234 0 -0.3675002 -0.930025 0 -0.3674964 -0.9300231 0 -0.3675011 -0.9300239 0 -0.3674992 -0.9300236 0 -0.3675 -0.9300234 0 -0.3675006 -0.929995 7.22553e-5 -0.3675725 -0.9300566 0 -0.3674164 -0.9300234 0 -0.3675003 -0.9300239 3.50356e-7 -0.3674991 -0.9301052 -6.46244e-5 -0.3672933 -0.02243119 -0.9968212 -0.07644796 0.01147627 -0.9997931 -0.01679748 1.30835e-6 -0.9996908 -0.02486783 -4.76696e-7 -0.9996908 -0.02486747 -4.96624e-7 -0.9996908 -0.02486795 0.005420148 -0.9996145 -0.02723461 0 -0.9996882 -0.02497076 -1.55446e-4 -0.9996884 -0.02496296 0.7063782 -0.6979632 0.1178013 0.7080474 -0.696235 0.118008 0.01599568 4.06376e-4 0.9998721 0.008075892 0 0.9999674 0.9996699 -2.27602e-4 -0.02569442 0.9987404 0.001186668 -0.0501635 0.8902831 -0.430817 0.1476246 0.8906005 -0.4298819 0.148433 0.9881691 0 0.153369 0.9883704 -0.00123018 0.1520615 0 -0.7071003 -0.7071133 0 -0.7071208 -0.7070928 0 -0.7071114 -0.7071022 0 -1 0 0 -0.6958761 0.7181619 -0.0427584 -0.7064561 0.7064641 0 0.6992917 0.7148365 -0.0288555 0.7068134 0.7068113 0 1 0 0 1 -1.81216e-7 0 0.7071208 -0.7070928 0 0.7071003 -0.7071133 0 0.7071114 -0.7071022 0.8899766 0.4317647 0.1467006 0.8906522 0.4297717 0.148442 0.7080474 0.696235 0.118008 0.7063782 0.6979632 0.1178013 0.1336 0.9469227 -0.2923841 0.1325078 0.9476784 -0.2904263 0.3549155 0.9210444 -0.160351 0.3560283 0.920775 -0.159428 0.354038 0.9209923 -0.1625742 0.7379899 0.6745941 -0.01714062 0.01147615 0.9997931 -0.01679748 -0.02243208 0.9968213 -0.07644695 -7.15044e-7 0.9996908 -0.02486729 1.30835e-6 0.9996908 -0.02486783 -3.72468e-7 0.9996908 -0.02486795 0 0.9996882 -0.02497088 0.005420148 0.9996145 -0.02723479 -1.55446e-4 0.9996884 -0.0249632 -0.5801453 0.3780034 -0.721488 -0.5800324 0.378035 -0.7215623 0.55771 0.8298223 -0.01883411 0.5579909 0.8296365 -0.01869821 0.03047734 0.9562867 -0.2908384 0.2382345 0.8700309 -0.4316139 0.3266646 0.9320301 -0.1568763 0.06888711 0.953287 -0.2941063 0.06833529 0.9543398 -0.2908025 0.05608993 0.9542069 -0.2938421 0 0.9563062 -0.2923675 1.79101e-5 0.956305 -0.2923713 0.001792907 0.9559022 -0.2936801 0.001622796 0.9558642 -0.2938044 0.001306116 0.955954 -0.293514 0.007175564 0.9563875 -0.292013 -0.08648568 0.8987867 -0.4297708 0.8512246 0.3335417 -0.4051748 0.7658922 0.4166875 -0.489674 0.6643163 0.483856 -0.5697081 0.7608858 0.4133099 -0.5002279 0.652562 0.4832528 -0.583635 0.8658859 0.4745544 -0.15824 0.8087851 0.544397 -0.2224828 0.8239999 0.518743 -0.2278817 0.7428516 0.5873998 -0.3211433 0.6905506 0.6185734 -0.3748422 0.6361681 0.6807383 -0.3631605 0.8036046 0.4559215 0.382564 0.6944097 0.5512102 0.4625607 0.6948171 0.5509285 0.4622845 0.694713 0.5509303 0.4624388 0.6950233 0.5502668 0.4627627 5.92104e-5 0.9872884 0.1589398 -1.25059e-4 0.987259 0.1591218 0 0.9872683 0.1590636 -0.9199826 0.3916062 -0.01663684 -0.8857289 0.461517 -0.04986399 -0.8924302 0.4511765 -0.002870738 -0.9272928 0.3736776 -0.02220684 -0.9501767 0.3063141 0.05775898 -0.9021987 0.4019623 0.1564095 -0.4181836 0.8548094 0.3072838 -0.8978105 0.3821629 0.2188327 -0.9781177 0.18355 0.09795612 -0.9545704 0.2881859 0.07579171 -0.9970384 -0.03789782 0.06692135 -0.9771502 -0.191191 0.09286206 -0.9310722 -0.3412432 0.1290651 -0.9952203 -0.0759595 0.06137496 -0.9580652 -0.2856448 0.02276879 -0.9332054 -0.358498 -0.02463626 -0.9559177 -0.2919124 0.03175926 0.9999994 -0.001013159 4.5154e-4 1 3.27415e-4 -2.81413e-4 1 4.1715e-5 3.65594e-5 1 -4.36337e-7 0 1 -2.59539e-7 0 1 5.96351e-5 3.16343e-5 1 4.24126e-7 0 1 -2.96715e-7 0 1 -6.24151e-7 0 1 -2.83354e-6 0 1 8.83753e-5 3.17563e-5 1 0 0 1 6.70159e-7 0 1 5.68404e-7 0 0.9998288 -5.25589e-4 0.01850342 1 -7.30405e-7 0 0.999995 -3.6949e-4 0.003176331 0.9999994 -4.19898e-4 0.001154184 0.9999997 -4.99584e-4 7.59053e-4 1 2.95076e-7 0 1 -2.71277e-7 0 0.9999997 -6.29199e-4 5.93103e-4 1 0 0 0.9999995 -8.84949e-4 5.10116e-4 0.9999986 -0.001661002 4.95075e-4 1 0 0 1 1.56331e-6 0 0.6817605 0.4170839 -0.6010355 0.681816 0.4170709 -0.6009815 0.6773747 0.2187992 -0.7023464 0.6775811 0.2189314 -0.7021061 0.6760532 -1.77111e-5 -0.7368529 0.6760721 -2.58824e-7 -0.7368355 0.6776029 -0.2189243 -0.7020872 0.6773657 -0.2187942 -0.7023566 0.6818216 -0.4170675 -0.6009776 0.6817607 -0.4170827 -0.6010361 -1.88771e-5 -0.6095932 -0.7927145 1.33717e-5 -0.6095912 -0.7927161 -2.07057e-5 -0.6095708 -0.7927318 1.3219e-5 -0.6096056 -0.792705 0 -0.6095695 -0.7927327 -0.001064538 -0.6105012 -0.7920147 -2.27027e-4 -0.6095125 -0.7927765 -8.25572e-5 -0.6097613 -0.7925853 -1.00747e-4 -0.6098327 -0.7925303 -1.166e-4 -0.6097328 -0.7926071 -1.46618e-4 -0.6096455 -0.7926743 -8.39597e-5 -0.6098526 -0.7925149 1.70818e-5 -0.6095961 -0.7927122 1.8846e-4 -0.6091955 -0.7930201 -3.07272e-6 -0.6096018 -0.7927079 -1.09461e-4 -0.6097427 -0.7925994 2.62306e-6 -0.6095989 -0.7927101 1.18386e-5 -0.6095992 -0.7927098 3.6165e-5 -0.6095721 -0.7927307 -2.32034e-5 -0.6096224 -0.7926921 -3.4103e-5 -0.6095921 -0.7927154 8.95724e-5 -0.6094518 -0.7928232 -0.08025091 -0.9967131 -0.01108992 -0.08521848 -0.9958863 -0.03079837 0 -0.9995222 -0.0309115 0 -0.9995222 -0.03091067 3.38106e-4 -1 -3.74846e-4 4.3764e-5 -0.9999999 5.81274e-4 -8.17717e-6 -1 1.36695e-4 -1.18067e-4 -1 -6.80703e-5 3.9788e-5 -1 2.80878e-5 4.50788e-5 -1 -7.36846e-5 -1.21038e-5 -1 -2.4642e-4 -8.0916e-5 -1 -2.12261e-4 7.86986e-4 -0.9999976 0.002076625 -6.72299e-5 -1 3.03286e-4 -2.88981e-4 -0.9999999 -5.56817e-4 -3.22861e-5 -1 -8.67543e-6 -7.85672e-6 -1 1.91697e-4 -7.21957e-5 -0.3234447 -0.9462471 1.63062e-4 -0.3220422 -0.9467254 -0.5667917 -0.195946 -0.8002203 -0.5623947 -0.1935204 -0.8039043 0 -0.7660444 0.6427876 0 -0.6427872 -0.7660448 0 -0.6427881 -0.7660442 -0.5612498 0 -0.8276466 -0.5608267 2.88395e-4 -0.8279332 -0.5623722 0.1933495 -0.8039612 -0.5669732 0.1958848 -0.8001066 0 0.6427872 -0.7660448 0 0.6427881 -0.7660442 0 0.7660453 0.6427867 -1 -2.2692e-7 0 0.01084417 0.9931393 -0.1164342 -0.01342231 0.9884831 -0.1507347 0.02034151 0.9937469 0.1097882 -0.02258574 0.9835162 0.1794043 -1 3.44244e-6 0 -1 1.63894e-5 -2.80118e-5 -1 -1.03297e-6 0 -1 4.32087e-6 4.3191e-6 -1 6.38254e-6 3.63142e-6 -1 4.4522e-7 0 -1 1.02878e-5 3.65386e-6 -1 4.19655e-7 0 -1 8.53709e-7 0 -1 8.82868e-7 0 -1 -1.11071e-6 0 -1 1.44978e-6 0 -1 2.34372e-6 0 -1 -1.92374e-5 4.9445e-6 -1 -1.9485e-6 0 -1 1.86846e-5 5.11558e-6 -1 -1.63899e-5 -2.80126e-5 -1 4.29129e-7 0 -1 -4.32087e-6 4.3191e-6 -1 -1.00819e-6 0 -1 -5.85064e-6 3.63141e-6 -1 1.88982e-6 0 -1 -1.27822e-6 0 -1 -1.02879e-5 3.65388e-6 -1 -5.91005e-7 0 0.02034074 -0.9937469 0.1097884 -0.02258014 -0.9835163 0.1794043 0.01084363 -0.9931392 -0.1164343 -0.01342219 -0.9884833 -0.1507336 -1 2.2692e-7 0 -1 -3.26272e-4 -2.86549e-5 -0.02753454 -0.9886995 0.1473605 -0.008887887 -0.9873418 0.1583583 -0.01205563 -0.986704 0.1620801 0 -0.9872767 0.1590117 0.7033671 -0.6916213 0.1641182 0.7033644 -0.6916239 0.1641187 0.7033627 -0.6916251 0.1641212 1 -4.58278e-6 0 1 -2.6378e-6 0 1 -2.91443e-6 0 1 2.59021e-7 0 1 2.93427e-5 0 1 2.80018e-6 0 1 2.3776e-6 0 1 1.2613e-7 0 1 1.9273e-7 0 1 -4.37932e-6 0 1 -4.24016e-6 0 1 1.01746e-5 0 1 -3.34905e-6 0 0.9881446 0 0.1535257 0.9880486 -3.09982e-4 0.1541429 0.9871251 -3.56019e-4 0.15995 0.9872855 -0.001354813 0.1589516 0.8811389 -0.4262183 0.204774 0.8812605 -0.4255554 0.2056275 0.8812661 -0.4255462 0.2056228 0.8810492 0.426702 0.2041519 0.8812661 0.4255462 0.2056228 0.8812605 0.4255554 0.2056275 0.7033671 0.6916213 0.1641184 0.7033624 0.6916258 0.1641196 0.7033631 0.6916255 0.1641172 -1.64944e-5 0.6095685 -0.7927335 2.42394e-6 0.609593 -0.7927146 0 0.6095787 -0.7927257 -0.00104767 0.6105958 -0.7919418 7.9254e-5 0.6096339 -0.7926832 -7.56778e-5 0.6098396 -0.7925249 -7.82289e-5 0.6098612 -0.7925083 -1.35335e-4 0.6096788 -0.7926486 -2.38888e-4 0.6095098 -0.7927786 -1.73332e-4 0.6096142 -0.7926982 -8.30246e-5 0.6098436 -0.7925218 -3.90452e-5 0.6095849 -0.7927208 -3.00709e-5 0.6096324 -0.7926843 -2.25201e-6 0.6095947 -0.7927134 3.40255e-5 0.6095915 -0.7927157 1.04797e-5 0.6095991 -0.79271 1.19697e-5 0.6095978 -0.7927109 -3.75711e-6 0.609601 -0.7927084 -8.81611e-6 0.6096433 -0.792676 0 0.6095896 -0.7927173 4.83381e-5 0.6094999 -0.7927863 1.10059e-4 0.6095934 -0.7927142 -0.02753609 0.9886999 0.1473585 -0.008886873 0.9873418 0.158358 -0.01215624 0.9867186 0.1619839 0 0.9872767 0.1590123 -1 3.26272e-4 -2.86549e-5 -1.05089e-4 0.3236607 -0.9461733 1.59823e-4 0.3220345 -0.9467279 0 0.9996395 -0.02685236 0 0.9996395 -0.02685236 -0.09638649 0.995301 -0.009252429 -0.1023648 0.9943884 -0.02671056 -0.9289736 0.3694826 -0.022156 -0.9580538 0.2856677 0.02295434 -0.9953789 0.08560484 0.04350441 -0.994078 -0.1085477 0.00512582 -0.9817113 -0.1899574 -0.01262027 -0.981688 -0.1900745 -0.01265919 -0.920524 -0.3808237 -0.08723008 0 -0.9156811 -0.4019058 0 -0.9156811 -0.4019057 0 -0.7760942 -0.6306172 0 -0.7760943 -0.6306169 0 -0.6619226 -0.7495722 0 -0.6619231 -0.7495718 0 -0.5381728 -0.8428347 0.001304686 -0.5354806 -0.8445465 -9.34539e-4 -0.3717756 -0.9283221 0 -0.3686498 -0.9295684 0 -0.1557525 -0.9877961 0 -0.1557525 -0.9877962 0 0.23678 -0.9715633 0 0.2367801 -0.9715633 0 0.5427367 -0.839903 0 0.5427367 -0.839903 0 0.7317696 -0.6815522 0 0.7317693 -0.6815525 0 0.9136198 -0.4065698 0 0.9136197 -0.40657 0.001386761 0.1205421 0.9927073 -0.001571655 0.1199269 0.9927816 0.001089572 0.3546022 0.9350168 -0.001339495 0.3541226 0.9351981 8.41987e-4 0.5680642 0.8229839 -0.00110203 0.5677193 0.8232215 5.69579e-4 0.7485105 0.6631228 -7.80175e-4 0.7483091 0.6633498 3.9623e-4 0.8854559 0.4647234 -6.29986e-4 0.8853607 0.4649045 1.36203e-4 0.970942 0.2393149 -1.19209e-4 1 0 -3.70233e-4 0.9709169 0.2394167 1.23821e-4 0.970942 -0.2393149 -1.19209e-4 1 0 3.71466e-4 0.885456 -0.4647234 -3.71307e-4 0.9709172 -0.2394154 5.94343e-4 0.7485104 -0.6631227 -6.18841e-4 0.885361 -0.4649038 7.92458e-4 0.5680642 -0.822984 -8.41628e-4 0.7483063 -0.6633529 0.001089572 0.3546022 -0.9350168 -0.001138627 0.567723 -0.823219 0.001386761 0.1205356 -0.9927081 -0.001336693 0.3541223 -0.9351982 -0.001584231 0.1199208 -0.9927823 0.001088678 -0.08560109 -0.996329 0.1096478 -0.117021 -0.987058 0.1269634 -0.3489305 -0.9285084 -0.05561238 -0.2551907 -0.9652901 0.1200776 -0.5619543 -0.8184064 -0.09112924 -0.4433043 -0.8917269 0.1142181 -0.7424077 -0.6601403 -0.07511854 -0.6381453 -0.7662427 0.1087512 -0.8796538 -0.4630144 -0.06170922 -0.7986287 -0.598652 0.1030252 -0.9656397 -0.238591 -0.05063349 -0.9159058 -0.3981868 0.09659081 -0.9953242 0 -0.04170966 -0.9835337 -0.1758459 0.08905053 -0.96697 0.2388288 -0.03468626 -0.9978166 0.05620545 0.08005404 -0.8822265 0.4639695 -0.02918606 -0.9579921 0.2853062 0.06926143 -0.7460275 0.6623035 -0.02471703 -0.8662499 0.4989992 -0.02051174 -0.7276059 0.6856886 -0.02157634 -0.5684479 0.8224363 0.06386977 -0.5485251 0.8336912 -0.01080757 -0.3549362 0.9348281 0.04397898 -0.3415248 0.9388433 0.001584887 -0.1205421 0.992707 0.02241188 -0.1155568 0.9930481 2.73922e-5 -8.76385e-6 -1 4.91291e-5 1.0914e-4 -1 -0.928549 0.3091896 -0.2054232 -0.9990762 -0.02172964 -0.03707581 0.1652448 -0.7781142 0.6059971 -0.9954824 -0.04161429 0.08534127 0.280762 -0.7025572 0.6539008 -0.9058795 -0.3441883 0.2468134 -0.7481626 -0.5269697 0.403182 -0.8507187 -0.3712948 0.3720458 0.567901 -0.6654755 0.4843873 -0.5680481 -0.6249881 0.5354545 0.6632363 -0.5406243 0.5175355 -0.3545746 -0.7203517 0.5961295 -0.568776 -0.6250394 0.534621 0.8828669 -0.3898783 0.2618035 -0.1205586 -0.7626213 0.6355113 -0.3382644 -0.71881 0.6073626 -0.08298879 -0.751267 0.6547602 0.9271371 -0.2572634 0.2724563 0.9983903 -0.05669009 0.001793622 0.9706501 0.1674678 -0.1726064 0.9955387 0.09244811 -0.01887696 0.8854565 0.3559439 -0.2987821 0.7482598 0.491071 -0.4460456 0.852647 0.4256696 -0.3029826 0.5680531 0.6351494 -0.5233556 0.5690827 0.6340844 -0.5235285 0.3546261 0.7128118 -0.6050949 0.3383362 0.7225725 -0.6028413 0.1205283 0.7586618 -0.6402386 0.08306407 0.7731733 -0.6287316 -0.1652625 0.7361583 -0.6563226 -0.2820643 0.7607493 -0.5845513 -0.5682832 0.5986018 -0.5645619 -0.6655128 0.5985024 -0.4459682 -0.8831786 0.328937 -0.3343594 -0.2114599 -0.9533191 -0.2155632 0 0.2393163 0.9709417 0 0.2393175 0.9709414 0 -0.2393163 0.9709417 0 -0.9927087 -0.1205385 0 -0.2393175 0.9709414 0 -0.9927089 -0.1205372 0 -0.4647257 0.8854548 0 -0.9350163 -0.3546046 0 -0.4647279 0.8854537 0 -0.6631233 0.7485103 0 -0.6631234 0.7485102 0 -0.8229849 -0.5680633 0 -0.8229852 -0.5680628 0 -0.8229852 0.5680628 0 -0.8229849 0.5680633 0 -0.6631234 -0.7485102 0 -0.6631233 -0.7485103 0 -0.9350163 0.3546046 0 -0.4647259 -0.8854547 0 -0.9927088 0.1205378 0 -0.4647278 -0.8854537 0 -0.9927088 0.1205379 0 -0.2393163 -0.9709417 0 -0.2393175 -0.9709414 0 0.2393163 -0.9709417 0 0.2393175 -0.9709414 0 0.4647257 -0.8854548 0 0.4647279 -0.8854537 0 0.6631233 -0.7485103 0 0.6631234 -0.7485102 0 0.8229849 -0.5680633 0 0.8229852 -0.5680628 0 0.9350163 -0.3546046 0 0.9927088 -0.1205379 0 0.9927088 -0.1205378 0 0.9927089 0.1205372 0 0.9927087 0.1205385 0 0.9350163 0.3546046 0 0.8229849 0.5680633 0 0.8229852 0.5680628 0 0.6631234 0.7485102 0 0.6631233 0.7485103 0 0.4647259 0.8854547 0 0.4647278 0.8854537 0 0.9996394 -0.02685272 0 0.9996394 -0.02685421 0 0.9136196 -0.4065703 0 0.9136199 -0.4065695 0.00100094 0.7317695 -0.6815515 0 0.7282431 -0.685319 0.007686972 0.7261043 -0.6875417 0 0.5427364 -0.8399032 -0.002847373 0.5410245 -0.8410021 0 0.2367797 -0.9715634 0 0.2367798 -0.9715634 0 -0.1557527 -0.9877961 0 -0.1557524 -0.9877961 0 -0.3686498 -0.9295684 0.004040956 -0.3729107 -0.9278585 -0.0039469 -0.5354771 -0.8445405 0.01031887 -0.5464177 -0.8374493 -0.002585172 -0.6619209 -0.7495693 0 -0.6658499 -0.7460857 0 -0.7775912 -0.6287702 9.94643e-4 -0.7760939 -0.6306166 0 -0.7745761 -0.6324808 0 -0.9156813 -0.4019054 0 -0.9156811 -0.4019055 0 -0.9995222 -0.0309115 0 -0.9995222 -0.03091061 0.8935582 -0.4489474 -4.69748e-7 0.8935721 -0.4489197 -2.04796e-5 0.8935813 -0.4489015 -4.22938e-6 0.8935807 -0.4489025 6.36374e-7 0.8933735 -0.4493135 0.001120507 0.8861731 -0.4632865 -0.007938146 -0.007170855 0.4030205 -0.915163 0.01229721 0.2691972 -0.9630066 -0.00936532 -0.9821088 0.1880814 -0.01027011 -0.2246272 -0.9743907 0.006428182 -0.9424802 0.3342004 0.009353995 -0.4030125 -0.9151468 0.004244267 -0.7112225 0.7029542 -0.0070706 -0.6792794 -0.7338457 -0.001890182 -0.6792907 0.7338669 -0.0058766 -0.3721562 0.9281516 0.007074177 -0.8104183 -0.5858089 -0.007070779 -0.9424773 -0.3341956 0.01025891 -0.2246193 0.9743926 0.007074356 -0.9898314 -0.1420697 -0.01229923 0.2691903 0.9630085 0.007175743 0.4030097 0.9151676 -0.005110323 0.8401065 0.5423975 -0.002517342 0.8315346 0.5554674 -0.002776265 0.9944266 -0.1053953 0.004549026 0.9986144 -0.05242675 0.001874864 0.8104382 -0.5858212 0.00277692 0.8142468 -0.5805125 -0.007170855 0.4030197 -0.9151632 0.01230359 0.2691964 -0.9630067 -0.009364187 -0.9821085 0.1880832 -0.01026618 -0.2246276 -0.9743907 0.006428003 -0.9424844 0.3341885 0.009354054 -0.4030139 -0.9151461 -0.007068157 -0.6792758 -0.7338491 -0.001885354 -0.6792871 0.7338703 0.007074296 -0.8104108 -0.5858194 -0.007073163 -0.942478 -0.3341934 0.01025891 -0.2246202 0.9743924 0.007074356 -0.9898307 -0.1420744 -0.01230567 0.2691898 0.9630085 0.007168114 0.4030076 0.9151686 -0.005107104 0.8401079 0.5423952 -0.002521276 0.8315364 0.5554646 -0.002776265 0.9944268 -0.1053934 0.004549026 0.9986147 -0.05242294 0.001874864 0.8104371 -0.5858228 0.00277692 0.8142476 -0.5805111 0.9993674 0 0.03556299 0.9993597 0 0.03577858 0.9993674 0 0.03556323 0.9993622 -5.42809e-5 0.03570932 0.8935582 0.4489474 0 0.8935723 0.4489194 -3.68704e-5 0.89359 0.4488843 -7.8747e-6 0.8935875 0.4488892 4.08365e-6 0.8934332 0.4491952 0.001003921 0.8814458 0.4721061 -0.01301491 -0.9999965 0.001714646 -0.002043426 -0.9999914 -0.002891242 -0.002998769 -0.9709441 -0.1836153 -0.1534706 -0.9614421 -0.22323 -0.1606162 0.09509986 -0.7686651 -0.6325424 -0.8851782 -0.3398395 -0.317756 0.1205283 -0.7586618 -0.6402386 0.3545886 -0.7234975 -0.5922994 -0.797451 -0.4786053 -0.3674355 0.3657287 -0.7151321 -0.5956751 -0.748487 -0.502807 -0.43238 0.5678878 -0.6131489 -0.5491376 -0.528485 -0.631897 -0.5669301 -0.5815903 -0.6292642 -0.5155378 0.7485027 -0.5102764 -0.4235113 0.7096861 -0.5643989 -0.421663 -0.1607549 -0.7410635 -0.651907 -0.2439351 -0.7616496 -0.6003212 0.8851683 -0.3395698 -0.3180717 0.9709364 -0.1809798 -0.1566169 0.9496718 -0.2654671 -0.166286 0.9986371 0.05159133 0.007888197 0.9874496 0.08031326 0.1359895 0.8826677 0.3926325 0.2583361 0.8160029 0.4081416 0.4093409 0.5682533 0.6629725 0.487397 0.4717853 0.6432379 0.6030454 0.1258301 0.7908683 0.598911 0.02775883 0.7367157 0.6756327 -0.3109765 0.7508144 0.5827274 -0.4219912 0.6621511 0.6192572 -0.5678046 0.6488921 0.5064949 -0.7484902 0.504963 0.4298545 -0.7825874 0.4467739 0.4335322 -0.8850588 0.3751972 0.2754961 -0.970853 0.174633 0.1641574 -0.9676061 0.1913217 0.1647257 -0.1808874 0.9696847 -0.1642907 -0.9238598 0.3772665 -0.06444543 -0.9673404 0.2530404 -0.01494318 -0.9671589 0.2539315 0.01107865 -0.9945068 0.1040295 0.01158517 -0.9953597 0.0960952 0.004991769 -0.9916771 -0.1285972 -0.006275713 -0.9804415 -0.170493 -0.09832 -0.9326158 -0.3125161 -0.1804478 -0.1013482 -0.9109661 -0.3998366 -0.1246849 -0.7700382 -0.6256955 -0.1375616 -0.6556298 -0.7424462 -0.1359571 -0.5328063 -0.8352444 -0.1690692 -0.3671379 -0.9146724 -0.1001546 -0.1549693 -0.9828295 -0.06960529 0.2362058 -0.9692069 -0.118236 0.5389294 -0.8340116 -0.1259678 0.7259402 -0.6761234 -0.08101511 0.9106166 -0.4052333 1 5.93294e-7 0 1 -7.90584e-7 0 1 2.61408e-7 0 1 3.97393e-7 0 1 -5.1609e-7 0 1 3.9905e-7 0 1 0 0 1 -4.0097e-7 0 1 1.04561e-6 0 1 -3.92746e-7 0 1 0 0 1 -3.95289e-7 0 1 -5.16094e-7 0 1 3.97396e-7 0 1 7.98105e-7 0 0.9996574 0.02617728 0 0.9996574 0.02617675 3.06286e-7 0.9996574 0.02617758 0 0.9996574 0.02617728 0 0.9996574 0.02617681 3.1356e-7 0.9996574 0.02617627 0 0.9996574 0.02617543 0 0.9996574 0.02617722 7.29156e-7 0.9996573 0.02617734 -1.68935e-7 0.9996573 0.02617698 -1.06208e-6 0.9996574 0.02617734 -5.35312e-7 0.9996574 0.02617818 0 0.9996573 0.02617782 0 0.9996573 0.02617669 0 0.9996573 0.02617746 8.03238e-7 0.9996573 0.02617853 0 0.9996574 0.02617764 5.52378e-7 0.9996573 0.0261777 7.68147e-7 0.9996574 0.02617764 -4.92195e-7 0.9996573 0.02617704 -1.85752e-7 0.9996574 0.02617681 2.3434e-7 0.9996574 0.02617722 0 0.9996573 0.02617847 3.80726e-7 0.9996573 0.02617758 7.04215e-7 0.9996573 0.02617663 3.03796e-7 0.9996575 0.02617532 2.089e-7 0.9996573 0.0261774 1.23224e-7 4.56875e-5 -0.6428543 -0.7659886 -5.90206e-5 -0.6427751 -0.7660551 1.74649e-5 -0.642768 -0.766061 -1.87511e-5 -0.6427967 -0.7660368 1.74413e-5 -0.642782 -0.7660492 3.8044e-6 -0.642794 -0.7660391 -1.93546e-6 -0.6428373 -0.7660029 -6.25483e-6 -0.6427937 -0.7660394 0 -0.6427503 -0.7660759 -9.31352e-5 -0.6427841 -0.7660474 -5.21953e-6 -0.642786 -0.7660459 7.67768e-5 -0.6427881 -0.7660441 0 -0.6427822 -0.7660491 4.97834e-6 -0.642832 -0.7660073 0 -0.6427888 -0.7660434 0 -0.6427994 -0.7660346 1.50854e-5 -0.6427453 -0.7660801 -1 -4.63306e-7 0 -1 8.47452e-7 0 -1 1.38986e-6 0 -1 -1.69498e-6 0 -1 1.85317e-6 0 -1 4.23735e-7 0 -1 4.63286e-7 0 -1 -1.27124e-6 0 -1 -4.6332e-7 0 -1 -1.85314e-6 0 -1 9.26557e-7 0 -1 -8.47498e-7 0 -1 -8.47504e-7 0 -1 1.27124e-6 0 -1 9.26554e-7 0 -1 -2.1187e-6 0 -1 3.70637e-6 0 -1 -1.69501e-6 0 -1 8.47509e-7 0 -1 -2.77978e-6 0 -1 3.38992e-6 0 -1 -9.2653e-7 0 -1 1.38987e-6 0 0.9397702 0.2351584 -0.2480575 0.8900526 0.007049858 -0.4558034 0.8910498 -8.09495e-4 -0.4539052 0.8907792 0.003909647 -0.4544196 0.890435 7.29072e-4 -0.4551098 0.8902996 2.30285e-4 -0.4553753 0.8903773 3.55033e-4 -0.4552232 0.9370213 -0.2376967 -0.255913 0.9360491 -0.2362833 -0.2607347 0.962858 -0.2275749 -0.1453069 0.9622734 -0.2359626 -0.1354678 1 5.19517e-7 0 1 3.24979e-7 0 1 4.83327e-7 0 1 2.68056e-6 0 1 1.44262e-6 0 1 -1.62503e-7 0 0.9999977 -5.80578e-5 0.002146959 0.9999982 0 0.00195825 0.96227 0.2359152 -0.1355749 0.9628317 0.2279166 -0.1449453 8.37015e-5 0.6428039 -0.7660308 2.56062e-4 0.6428239 -0.766014 -1.32463e-4 0.6427369 -0.7660871 1.21772e-5 0.6426189 -0.766186 0 0.6427911 -0.7660416 0 0.6427949 -0.7660384 8.37052e-5 0.64277 -0.7660592 -1.25252e-5 0.6427885 -0.7660437 2.33562e-5 0.6427755 -0.7660546 1.30308e-5 0.6428071 -0.7660282 -2.51097e-4 0.6428356 -0.7660042 -4.60523e-5 0.6428485 -0.7659933 -5.93044e-5 0.6427429 -0.766082 -1.39703e-4 0.6427863 -0.7660456 -4.92562e-6 0.6427842 -0.7660474 -4.62771e-6 0.6427754 -0.7660548 -3.19228e-5 0.6427606 -0.7660671 -3.87536e-5 0.6427826 -0.7660486 -0.9363436 0.3070313 -0.1702719 -0.9810276 0.1926141 -0.02201992 -0.9952505 0.09579926 -0.01729279 -0.998455 0.04890769 -0.02637636 -0.982537 -0.09323632 -0.161022 -0.9297438 -0.3109241 -0.1972377 -0.1580601 -0.8335986 -0.5292737 -0.1565418 -0.689107 -0.7075495 -0.2045023 -0.412797 -0.8875684 -0.2031112 0.001061677 -0.9791552 -0.1717626 0.3776857 -0.9098632 -0.1764627 0.6551152 -0.7346326 -0.1556944 0.8623968 -0.481696 0.03992599 -0.2349029 0.9711985 0.07509958 0 0.9971761 -0.0245471 -0.07998585 0.9964937 -0.06446444 0.1117244 0.9916461 0.07361644 0.2386696 0.9683065 0 0.9937121 -0.1119655 0.01996117 0.9925112 -0.1205121 0.06904077 0.4636125 0.8833442 -0.06139671 0.3296662 0.942099 0.03686279 0.9343799 -0.3543663 -0.01845443 0.9437231 -0.3302217 0.06136345 0.6618745 0.7470989 -0.05527955 0.5312152 0.8454317 0.0506758 0.8219277 -0.5673331 -0.03380894 0.8462406 -0.5317273 0.0506758 0.8219277 0.5673331 -0.04605776 0.7063578 0.706355 0.06138414 0.6618736 -0.747098 -0.0460633 0.7063576 -0.7063548 0.03686279 0.9343799 0.3543663 -0.03380054 0.8462409 0.5317272 0.06904077 0.4636125 -0.8833442 -0.05525726 0.5312156 -0.8454329 0.01996117 0.9925112 0.1205121 -0.01845514 0.9437231 0.3302215 0 0.9937121 0.1119655 0.07361644 0.2386696 -0.9683065 -0.06139695 0.3296582 -0.9421018 0.07514077 0 -0.997173 -0.06448662 0.1117328 -0.9916438 0.07994925 -0.2385527 -0.9678331 -0.07355016 -0.1189643 -0.9901707 0.08464115 -0.4630531 -0.8822799 -0.0781669 -0.3464453 -0.9348078 0.08875429 -0.6605072 -0.7455556 -0.08250379 -0.5545424 -0.8280555 -0.08594602 -0.7319368 -0.6759304 0.09180533 -0.8195096 -0.5656641 -0.08787125 -0.8690117 -0.4869264 0.09308093 -0.930956 -0.3530681 -0.0878213 -0.958458 -0.2713779 0.09220057 -0.9884807 -0.1200211 -0.08539962 -0.995504 -0.04097306 0.08887612 -0.9887806 0.1200585 -0.0806142 -0.9781084 0.1918472 0.08327108 -0.931768 0.353376 -0.07386523 -0.907064 0.4144621 0.0759015 -0.820611 0.5664244 -0.06579798 -0.7860333 0.6146727 0.06734198 -0.6616185 0.7468106 -0.05721032 -0.6214671 0.7813488 0.05839562 -0.4639279 0.8839462 -0.04853707 -0.4223544 0.9051304 0.04953569 -0.2390253 0.9697491 0 0.4647201 0.8854576 0 0.2393213 0.9709405 0 0.9927089 -0.1205372 0 0.6631239 0.7485097 0 0.4647187 0.8854585 0 0.8229863 0.5680614 0 0.9350165 -0.3546046 0 0.6631234 0.7485101 0 0.9927088 -0.1205376 0 0.9350167 0.354604 0 0.8229846 0.5680637 0 0.8229857 -0.5680623 0 0.9350159 -0.354606 0 0.9350156 0.3546068 0 0.6631234 -0.7485101 0 0.8229852 -0.5680629 0 0.9927088 0.1205376 0 0.6631239 -0.7485097 0 0.4647201 -0.8854576 0 0.2393221 -0.9709403 0 0.4647187 -0.8854585 0 0.2393214 -0.9709405 0 -0.2393221 -0.9709403 0 -0.2393214 -0.9709405 0 -0.46472 -0.8854578 0 -0.6631239 -0.7485097 0 -0.4647188 -0.8854583 0 -0.8229863 -0.5680614 0 -0.6631234 -0.7485101 0 -0.8229846 -0.5680637 0 -0.9350167 -0.354604 0 -0.9350156 -0.3546068 0 -0.9927088 -0.1205376 0 -0.9927089 0.1205372 0 -0.9927088 0.1205376 0 -0.9350165 0.3546046 0 -0.9350159 0.354606 0 -0.8229857 0.5680623 0 -0.8229852 0.5680629 0 -0.6631234 0.7485101 0 -0.6631239 0.7485097 0 -0.46472 0.8854578 0 -0.4647188 0.8854583 0 -0.2393221 0.9709403 0 -0.2393214 0.9709405 0 0.2393221 0.9709403 0.9665685 0 -0.2564088 0.9666215 1.21341e-4 -0.256209 -0.9446704 0.2713601 -0.1842861 -0.9883738 0.01459109 -0.1513425 -0.934621 -0.1778659 -0.307973 -0.9265457 -0.2626262 -0.2693336 -0.9250262 -0.1589725 -0.3450428 -0.9258213 6.90148e-4 -0.377961 -0.8987936 0.1668682 -0.4053704 -0.9338782 0.2361457 -0.2685271 1 1.089e-6 0 1 -3.70103e-7 0 1 -3.8117e-7 0 1 0 0 1 2.05321e-7 0 1 7.40179e-7 0 1 -2.45521e-7 0 -1 -2.97598e-6 0 -1 7.77586e-7 0 -1 -2.97605e-6 0 -1 -6.05363e-7 0 -1 2.02328e-6 0 -1 4.29314e-7 0 -1 -4.14777e-7 0 -1 3.72677e-7 0 -1 2.02326e-6 0 -1 2.97605e-6 0 -0.9454235 0.2289243 -0.2318797 -0.9718704 0.07209581 -0.2242102 -0.9301618 0.01454931 -0.3668617 + + + + + + + + + + + + + + +

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

+
+
+
+ + + + -0.07899999 0.002613067 -0.4930827 -0.07899999 -0.02001917 -0.4930827 -0.07899999 -0.02001917 -0.4855386 -0.07899999 0.002614974 -0.5001272 -0.07899999 -0.02001917 -0.5045268 -0.07899999 -0.02001917 -0.497482 -0.07899999 0.009622275 -0.4954928 -0.07899999 0.009528458 -0.4930827 -0.07899999 0.02210193 -0.4855386 -0.07899999 0.005863189 -0.504288 -0.07899999 0.003994643 -0.5032325 -0.07899999 0.002903819 -0.5016368 -0.07899999 0.01091665 -0.4967517 -0.07899999 0.02210193 -0.4930827 -0.07899999 0.02210193 -0.5043988 -0.07899999 0.02210193 -0.4968547 -0.06949985 0.02210193 -0.4855386 -0.06949985 0.02210193 -0.4930827 -0.06949985 0.009528458 -0.4930827 -0.06949985 0.01089048 -0.496761 -0.06949985 0.009631514 -0.4954668 -0.06949985 0.02210193 -0.4968547 -0.06949985 0.02210193 -0.5043988 -0.06949985 0.005834341 -0.5043042 -0.06949985 0.003869354 -0.5031109 -0.06949985 0.002842366 -0.5014734 -0.06949985 0.002614974 -0.5001272 -0.06949985 -0.02001917 -0.5045268 -0.06949985 -0.02001917 -0.497482 -0.06949985 0.002613067 -0.4930827 -0.06949985 -0.02001917 -0.4930827 -0.06949985 -0.02001917 -0.4855386 -0.06949985 0.009528458 -0.5863811 -0.06949985 0.002613067 -0.5863811 -0.06949985 0.009528458 -0.5901531 -0.06949985 -0.01210463 -0.5789293 -0.06949985 0.02210193 -0.578837 -0.06949985 0.02210193 -0.5863811 -0.06949985 0.02210193 -0.5901531 -0.06949985 0.02210193 -0.5976972 -0.06949985 0.002613067 -0.5901531 -0.06949985 -0.01224619 -0.5975964 -0.06949985 -0.01755499 -0.5818204 -0.06949985 -0.01225024 -0.5873485 -0.06949985 -0.01130115 -0.5864615 -0.06949985 -0.01497143 -0.5799171 -0.06949985 -0.01940631 -0.5849231 -0.06949985 -0.02007812 -0.588061 -0.06949985 -0.01250165 -0.5884397 -0.06949985 -0.01908701 -0.5924944 -0.06949985 -0.0119062 -0.5896646 -0.06949985 -0.01614916 -0.5959593 -0.06949985 -0.01092058 -0.590133 -0.07899999 0.002613067 -0.5901531 -0.07899999 -0.01092964 -0.5901255 -0.07899999 -0.01181757 -0.5897431 -0.07899999 -0.01242184 -0.5887613 -0.07899999 -0.01234757 -0.5874211 -0.07899999 -0.01117861 -0.5864462 -0.07899999 0.002613067 -0.5863811 -0.07899999 0.009528458 -0.5901531 -0.07899999 0.009528458 -0.5863811 -0.07899999 0.02210193 -0.578837 -0.07899999 -0.01240748 -0.5789844 -0.07899999 0.02210193 -0.5863811 -0.07899999 0.02210193 -0.5976972 -0.07899999 0.02210193 -0.5901531 -0.07899999 -0.01229143 -0.5975592 -0.07899999 -0.01908701 -0.5840399 -0.07899999 -0.01684236 -0.5812085 -0.07899999 -0.01497143 -0.5799171 -0.07899999 -0.02007812 -0.5884732 -0.07899999 -0.01889538 -0.5928595 -0.07899999 -0.01580983 -0.5961935 -0.07899999 0.002613067 -0.5552817 -0.07899999 -0.02001917 -0.5552817 -0.07899999 -0.02001917 -0.5477376 -0.07899999 0.002614974 -0.5623262 -0.07899999 -0.02001917 -0.5667258 -0.07899999 -0.02001917 -0.559681 -0.07899999 0.009609103 -0.5576249 -0.07899999 0.009528458 -0.5552817 -0.07899999 0.003619611 -0.5649982 -0.07899999 0.002842366 -0.5636724 -0.07899999 0.02210193 -0.5477376 -0.07899999 0.006289124 -0.5665444 -0.07899999 0.004773855 -0.5660128 -0.07899999 0.01085072 -0.5589357 -0.07899999 0.02210193 -0.5552817 -0.07899999 0.02210193 -0.5665978 -0.07899999 0.02210193 -0.5590538 -0.06949985 0.02210193 -0.5477376 -0.06949985 0.02210193 -0.5552817 -0.06949985 0.009528458 -0.5552817 -0.06949985 0.0109573 -0.5589731 -0.06949985 0.009646475 -0.5577315 -0.06949985 0.02210193 -0.5590538 -0.06949985 0.02210193 -0.5665978 -0.06949985 0.005834341 -0.5665032 -0.06949985 0.003937304 -0.5653654 -0.06949985 0.002903819 -0.5638358 -0.06949985 0.002614974 -0.5623262 -0.06949985 -0.02001917 -0.5667258 -0.06949985 -0.02001917 -0.559681 -0.06949985 0.002613067 -0.5552817 -0.06949985 -0.02001917 -0.5552817 -0.06949985 -0.02001917 -0.5477376 -0.07899999 0.01322668 -0.5239524 -0.07899999 -0.02001917 -0.5163594 -0.07899999 0.01418745 -0.5164517 -0.07899999 -0.02001917 -0.5239034 -0.07899999 0.01789253 -0.5178629 -0.07899999 0.0141198 -0.524562 -0.07899999 0.01344615 -0.5275818 -0.07899999 -0.02001917 -0.5352196 -0.07899999 -0.02001917 -0.5276755 -0.07899999 0.02097815 -0.521197 -0.07899999 0.01457047 -0.5255589 -0.07899999 0.02203321 -0.5246528 -0.07899999 0.0143283 -0.5351188 -0.07899999 0.02193456 -0.5278601 -0.07899999 0.01437157 -0.5266347 -0.07899999 0.0170542 -0.5341394 -0.07899999 0.02043265 -0.5311464 -0.07899999 0.01892513 -0.532848 -0.06949985 0.01449024 -0.5165069 -0.06949985 0.0170542 -0.5174395 -0.06949985 0.01892513 -0.5187309 -0.06949985 0.02043265 -0.5204325 -0.06949985 0.02148914 -0.5224455 -0.06949985 0.02203321 -0.5246528 -0.06949985 0.02183586 -0.5282604 -0.06949985 0.02043265 -0.5311464 -0.06949985 0.01789253 -0.533716 -0.06949985 0.01437348 -0.5350816 -0.06949985 -0.02001917 -0.5352196 -0.06949985 -0.02001917 -0.5276755 -0.06949985 0.0132125 -0.5239607 -0.06949985 0.0143671 -0.5248229 -0.06949985 0.01447576 -0.5264735 -0.06949985 0.01342111 -0.5275728 -0.06949985 -0.02001917 -0.5239034 -0.06949985 -0.02001917 -0.5163594 + + + + + + + + + + -1 0 0 -1 0 3.09129e-6 -1 -2.35795e-6 0 -1 0 -6.50692e-7 -1 0 5.9571e-6 -1 -1.27914e-6 8.27406e-7 -1 8.19137e-7 0 -1 9.46944e-7 -3.06264e-7 0 1 0 0 0 -1 -0.001092135 0.9990665 0.04318374 0 0.9992437 0.03888523 -0.002612888 0.7167965 0.6972776 0.002619564 0.6972117 0.7168605 0 0.008357048 0.9999651 9.90338e-4 0.00920248 0.9999572 0 -0.005814671 -0.9999832 -0.001726508 -0.006826937 -0.9999752 0.004114925 -0.519077 -0.8547176 -0.002988338 -0.4918026 -0.8707016 0.003657937 -0.8471717 -0.5313066 -0.003652393 -0.8255504 -0.5643165 0 -0.9860255 -0.1665947 -0.003118276 -0.9821726 -0.1879558 0 0.1908073 -0.9816275 0 0.1908076 -0.9816275 0 -1 0 0 -0.1908104 0.981627 0 -0.1908104 0.9816269 0 0 1 1 0 0 1 3.6507e-7 0 1 -3.65049e-7 0 1 0 -3.12517e-6 1 1.17741e-6 0 1 -1.94692e-6 6.27491e-7 1 7.30567e-6 0 1 -1.72034e-5 -6.58839e-6 1 1.28197e-6 -8.29673e-7 1 -4.20837e-7 3.05808e-7 1 -4.54284e-7 5.66624e-7 1 -4.84518e-7 -5.64633e-7 1 0 -1.9501e-6 1 -1.09033e-6 1.48068e-6 1 2.6001e-6 2.67409e-7 1 6.05644e-7 -2.34938e-6 1 0 -2.22513e-7 1 -1.75247e-6 0 1 2.77654e-6 0 1 4.64919e-7 0 1 -5.72398e-7 0 1 0 0 0 0.001488566 0.999999 7.96261e-4 0.002037703 0.9999976 -0.003447473 0.4291648 0.9032196 3.29561e-4 0.39551 0.9184617 -0.007246613 0.8993424 0.4371852 0.003613948 0.8516265 0.5241368 0.0102632 0.9984164 -0.05531328 -0.008267879 0.9744334 -0.2245244 -0.001405477 0.682813 -0.7305918 0.007019937 0.6404619 -0.767958 0 0.00577861 -0.9999833 -0.001535296 0.004723608 -0.9999877 -1 9.0431e-7 -5.63968e-7 -1 4.53365e-7 5.65477e-7 -1 1.09118e-6 1.88261e-6 -1 -1.70059e-6 8.1451e-7 -1 0 7.47959e-7 -1 -7.1764e-7 -4.5151e-7 -1 -1.75105e-6 0 -1 6.59039e-6 0 -1 1.75252e-6 0 -1 -6.52003e-6 0 -1 0 0 -1 0 0 0 -0.002697348 0.9999964 -0.005669951 -0.004272937 0.9999748 0.008917093 -0.3867837 -0.9221274 -0.001915216 -0.361844 -0.9322367 0.009462475 -0.7626985 -0.6466851 -0.009462416 -0.7338938 -0.6791984 0.009464919 -0.9758667 -0.2181622 -0.009469151 -0.9654726 -0.2603327 -0.01339852 -0.9777548 0.2093232 -0.009465038 -0.9758678 0.2181571 0.01877254 -0.8585948 0.5123111 -0.018772 -0.7834765 0.6211379 0 -0.5931211 0.8051134 0.0103811 -0.5680475 0.8229304 0.004897952 -0.3257741 0.9454349 0 -0.3418331 0.9397607 0 -0.002936124 -0.9999957 -0.003899157 -0.004013597 -0.9999844 -1 0 3.17959e-6 -1 -2.36237e-6 0 -1 0 -6.16521e-7 -1 0 1.22188e-5 -1 -3.65009e-6 6.44145e-6 -1 -6.2251e-6 -1.09857e-5 -1 0 7.20088e-7 -1 1.37153e-6 0 -1 9.65639e-7 -2.81909e-7 -0.003389537 0.9988358 0.0481224 0 0.9994081 0.03440135 -0.004863262 0.6876746 0.7260028 0.004846036 0.7259941 0.6876839 0 0.007241368 0.9999738 0.003807365 0.01049387 0.9999378 0 -0.005814671 -0.9999832 0.004178404 -0.003381073 -0.9999856 -0.01175844 -0.3309901 -0.943561 0.01314979 -0.5143329 -0.8574898 0.006073832 -0.8285785 -0.5598401 -0.006953179 -0.660205 -0.7510534 -0.003121554 -0.8626901 -0.5057234 0.003115296 -0.9821724 -0.1879569 0 -0.9860255 -0.1665944 1 3.65079e-7 0 1 -3.65045e-7 0 1 0 -3.04133e-6 1 2.3498e-6 0 1 0 6.6195e-7 1 -7.96686e-6 -5.97678e-6 1 -8.43227e-6 0 1 1.27532e-6 -8.36279e-7 1 -1.38466e-6 0 1 -4.21531e-7 3.10362e-7 -1 0 0 -1 -4.64166e-7 0 -1 4.99269e-7 0 -1 -7.02721e-6 0 -1 -4.61119e-7 0 -1 3.50135e-6 0 -1 -3.48416e-6 0 -1 0 -1.78499e-6 -1 0 0 -1 -6.10232e-7 2.30082e-6 -1 5.43768e-6 3.07015e-7 -1 -5.45128e-7 -2.11087e-6 -1 1.44615e-6 -6.85214e-7 -1 0 -8.23439e-7 -1 3.4009e-6 -6.56241e-7 -0.01172184 0.3418112 0.9396957 -0.005927145 0.3559431 0.9344889 0.01344227 0.5680087 0.8229129 -0.01038128 0.7484645 0.6630936 -0.01771438 0.7338106 0.6791232 0.01343643 0.8853837 0.4646669 0 0.970941 0.2393191 -0.01307266 0.9563378 0.2919715 0.008068442 0.9984752 -0.05460947 0 0.9995273 -0.0307455 0 0.8993313 -0.4372679 -0.008069276 0.9094902 -0.4156473 0.01306307 0.7111088 -0.7029607 0 0.7485037 -0.6631307 -0.01343691 0.5680084 -0.8229131 0.001928269 0.3617878 -0.9322585 0.01210081 0.338114 -0.9410275 0 0.002934396 -0.9999958 0.003887832 0.004011929 -0.9999844 0 -0.002799808 0.9999961 -9.61552e-4 -0.003071069 0.9999949 -0.001592636 -0.5983203 -0.8012555 -0.008011639 -0.5637035 -0.8259384 0.0124014 -0.9111507 -0.4118869 -0.01626878 -0.9977064 -0.06570672 0.007703065 -0.9833038 0.1818087 -0.002557814 -0.7216104 0.6922947 -0.00401622 -0.7152429 0.6988644 0 -0.001473665 -0.9999989 -8.84992e-4 -0.001723647 -0.9999982 0 0.002697348 0.9999964 0.005681335 0.004272937 0.9999748 1 4.48678e-7 0 1 -1.71809e-6 -6.63053e-7 1 -4.23959e-6 -8.12234e-7 1 0 4.68896e-7 1 5.30898e-6 -7.84612e-7 1 -3.45478e-6 -4.67187e-7 1 -1.71063e-6 -2.38251e-7 1 0 -2.03813e-6 1 7.17744e-7 0 1 1.22551e-6 2.30909e-6 1 0 6.84664e-7 1 0 -1.22958e-6 1 0 0 1 4.64353e-7 0 1 4.6344e-7 0 + + + + + + + + + + + + + + +

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

+
+
+
+
+ + + + + 0.6859207 -0.3240135 0.6515582 7.481132 0.7276763 0.3054208 -0.6141704 -6.50764 0 0.8953956 0.4452714 5.343665 0 0 0 1 + + + + -0.2908646 -0.7711008 0.5663932 4.076245 0.9551712 -0.1998834 0.2183912 1.005454 -0.05518906 0.6045247 0.7946723 5.903862 0 0 0 1 + + + + 1 0 0 0 0 1 0 0 0 0 1 0 0 0 0 1 + + + + + + + + + + 1 0 0 0 0 1 0 0 0 0 1 0 0 0 0 1 + + + + + + + + + + + + + +
\ No newline at end of file diff --git a/kuka_kr5_support/meshes/kr5_arc/visual/link_5.dae b/kuka_kr5_support/meshes/kr5_arc/visual/link_5.dae new file mode 100644 index 000000000..a75e1d894 --- /dev/null +++ b/kuka_kr5_support/meshes/kr5_arc/visual/link_5.dae @@ -0,0 +1,201 @@ + + + + + Blender User + Blender 2.79.0 commit date:2017-09-11, commit time:10:43, hash:5bd8ac9abfa + + 2017-11-10T20:09:19 + 2017-11-10T20:09:19 + + Z_UP + + + + + + + 49.13434 + 1.777778 + 0.1 + 100 + + + + + + 0 + 0 + 0 + + + + + + + + + 1 1 1 + 1 + 0 + 0.00111109 + + + + + 0 + 0 + 8192 + 1 + 1 + 1 + 1 + 0 + 0 + 0 + 1 + 29.99998 + 75 + 0.15 + 1 + 0 + 1 + 2 + 1.000799 + 30.002 + 1 + 3 + 0.04999995 + 2880 + 3 + 1 + 0 + 0 + 2 + 1 + 1 + 1 + 0 + 1 + 0.1 + 0.1 + 1 + 0.000999987 + 1 + 0 + 0 + 1 + 1 + 1 + 1 + 1 + 1 + 1 + 2 + 1 + 1 + 1 + 1 + 0 + + + + + + + + + + + + 0 0 0 1 + + + 0 0 0 1 + + + 1 0.4980392 0 1 + + + 0.5 0.5 0.5 1 + + + 0 + + + 1 1 1 1 + + + 1 + + + + + + + + + + + + + + + + 0.07349997 0.02499997 0.0520001 0.07206815 0.005809009 0.0520001 0.07313674 0.002991437 0.0520001 0.07035636 0.008288979 0.0520001 0.06810081 0.01028728 0.0520001 0.06543254 0.01168769 0.0520001 0.06250667 0.01240885 0.0520001 0.05949324 0.01240885 0.0520001 0.0485 0.02499997 0.0520001 0.05656743 0.01168769 0.0520001 0.05389916 0.01028728 0.0520001 0.05164361 0.008288979 0.0520001 0.04993176 0.005809009 0.0520001 0.07349997 0 0.0520001 0.0485 0 0.0520001 0.04886323 0.002991437 0.0520001 0.07349997 -0.02499997 0.04100012 0.0805 -0.02499997 0.04100012 0.0805 -0.009109854 0.04100012 0.0805 0.009109854 0.04100012 0.07349997 0.02499997 0.04100012 0.0805 0.02499997 0.04100012 0.0159201 0.0330193 -0.01434314 0.01137614 0.02883714 -0.02155029 0.008062243 0.02993321 -0.01999998 0.03030735 0.02883714 -0.02155029 0.03030735 0.03278446 -0.01487201 0.01788377 0.034419 -0.0105561 0.03030735 0.03520941 -0.007503032 0.02043038 0.03531652 -0.006982445 0.02507096 0.03596526 -0.001580297 0.03030735 0.03599935 2.14276e-4 0.02745467 0.03585034 0.003327429 0.03030735 0.03511756 0.007921636 0.04036921 0.03047478 -0.02155029 0.04210287 0.03475391 -0.01422619 0.04210287 0.03022485 -0.02228623 0.04210287 0.03717643 -0.005303919 0.04210287 0.03734564 0.003939747 0.04210287 0.03525131 0.01294469 0.03545224 0.03309661 0.01580631 0.04210287 0.03102028 0.02116507 0.03811055 0.02999866 0.02172595 0.03988331 0.0275976 0.02504664 0.04210287 0.02490913 0.02810257 0.04166644 0.02482241 0.02810257 0.03030735 -0.03599935 2.14276e-4 0.02745467 -0.03585034 0.003327429 0.02507096 -0.03596526 -0.001580297 0.03030735 -0.03511756 0.007921636 0.03030735 -0.03520941 -0.007503032 0.0213499 -0.03552466 -0.005833387 0.01805722 -0.03450375 -0.01028037 0.01137614 -0.02883714 -0.02155029 0.0159201 -0.0330193 -0.01434314 0.008062243 -0.02993321 -0.01999998 0.03030735 -0.03278446 -0.01487201 0.03030735 -0.02883714 -0.02155029 0.03881436 -0.02908223 0.02308744 0.04210287 -0.02490913 0.02810257 0.04166644 -0.02482241 0.02810257 0.04210287 -0.03102028 0.02116507 0.03707796 -0.03126543 0.01959717 0.04210287 -0.03525131 0.01294469 0.03545224 -0.03309661 0.01580631 0.04210287 -0.03734564 0.003939747 0.04210287 -0.03717643 -0.005303919 0.04210287 -0.03475391 -0.01422619 0.04036921 -0.03047478 -0.02155029 0.04210287 -0.03022485 -0.02228623 0.0485 -0.02742516 0.02810257 0.06243169 -0.02499997 0.03498566 0.0485 -0.02499997 0.03028029 0.0485 -0.02582836 0.02957683 0.06243169 -0.03188282 0.02885282 0.0485 -0.02663695 0.02885079 0.06243169 -0.03730016 0.02139377 0.06243169 -0.04100316 0.01295137 0.06243169 -0.04282146 0.0039137 0.06243169 -0.04267162 -0.0053038 0.04545319 -0.03027147 -0.02370834 0.06243169 -0.04056042 -0.01427757 0.06243169 -0.03658497 -0.0225951 0.05176007 -0.02639782 -0.03023928 0.06243169 -0.03092789 -0.02987408 0.05520868 -0.02330565 -0.03381043 0.06243169 -0.02384936 -0.03577995 0.0581972 -0.01976656 -0.0369051 0.06243169 -0.01567459 -0.04004126 0.0805 0.03412681 -0.02616018 0.0805 0.02729094 -0.03322952 0.06243169 0.03092789 -0.02987408 0.06243169 0.03658497 -0.0225951 0.0805 -0.02499997 0.03498566 0.0805 0.03917783 -0.01772266 0.06243169 0.04056042 -0.01427757 0.0805 -0.03229475 0.02839094 0.0805 0.04217982 -0.00835824 0.06243169 0.04267162 -0.0053038 0.0805 -0.0379005 0.02031129 0.0805 0.04297572 0.001443266 0.06243169 0.04282146 0.0039137 0.0805 -0.04152399 0.01116937 0.0805 0.04152399 0.01116937 0.06243169 0.04100316 0.01295137 0.0805 -0.04297572 0.001443266 0.0805 0.0379005 0.02031129 0.06243169 0.03730016 0.02139377 0.0805 -0.04217982 -0.00835824 0.0805 0.03229475 0.02839094 0.06243169 0.03188282 0.02885282 0.0805 -0.03917783 -0.01772266 0.0805 0.02499997 0.03498566 0.06243169 0.02499997 0.03498566 0.0805 -0.03412681 -0.02616018 0.0805 -0.02729094 -0.03322952 0.0805 -0.0190277 -0.03856086 0.06295299 -0.01464998 -0.04042738 0.0645861 -0.01210397 -0.04126125 0.0805 -0.00976932 -0.04187548 0.06590551 -0.009510934 -0.04193496 0.06740963 -0.005045413 -0.04270297 0.0805 0 -0.04299998 0.06798505 -5.23879e-4 -0.04299676 0.06762552 0.004003465 -0.04281318 0.0805 0.00976932 -0.04187548 0.06619185 0.008841574 -0.04208117 0.06295299 0.01464998 -0.04042738 0.0805 0.0190277 -0.03856086 0.06243169 0.01567459 -0.04004126 0.06243169 0.02384936 -0.03577995 0.0581972 0.01976656 -0.0369051 0.05455374 0.02396184 -0.03313225 0.04545319 0.03027147 -0.02370834 0.05026632 0.02749598 -0.02869248 0.0485 0.02742516 0.02810257 0.0485 0.02663695 0.02885079 0.0485 0.02582836 0.02957683 0.0485 0.02499997 0.03028029 0.02336663 0.02037149 -0.02155029 0.01787966 0.02532422 -0.02155029 0.02752512 0.01426059 -0.02155029 0.03011876 0.007338881 -0.02155029 0.03099995 0 -0.02155029 0.02752512 -0.01426059 -0.02155029 0.03011876 -0.007338881 -0.02155029 0.02336663 -0.02037149 -0.02155029 0.01787966 -0.02532422 -0.02155029 0.0485 -0.02499997 0.0520001 0.07349997 -0.02499997 0.0520001 0.007699131 0.0358392 -0.01434314 0.01623475 0.04072451 -0.001580297 0.006547749 0.0433495 -0.001580297 -9.54622e-4 0.03664439 -0.01434314 -0.003482341 0.04370272 -0.001580297 -0.009554684 0.03538966 -0.01434314 -0.01332998 0.04176557 -0.001580297 -0.0176177 0.03214555 -0.01434314 -0.02247905 0.03763967 -0.001580297 -0.02469038 0.02709442 -0.01434314 -0.03045004 0.03154116 -0.001580297 -0.03037506 0.02052021 -0.01434314 -0.03682529 0.0237897 -0.001580297 -0.03435224 0.0127924 -0.01434314 -0.04127061 0.01479154 -0.001580297 -0.03639835 0.004345536 -0.01434314 -0.04355311 0.005018174 -0.001580297 -0.04355311 -0.005018174 -0.001580297 -0.03639835 -0.004345536 -0.01434314 -0.04127061 -0.01479154 -0.001580297 -0.03435224 -0.0127924 -0.01434314 -0.03682529 -0.0237897 -0.001580297 -0.03037506 -0.02052021 -0.01434314 -0.03045004 -0.03154116 -0.001580297 -0.02469038 -0.02709442 -0.01434314 -0.02247905 -0.03763967 -0.001580297 -0.0176177 -0.03214555 -0.01434314 -0.01332998 -0.04176557 -0.001580297 -0.009554684 -0.03538966 -0.01434314 -0.003482341 -0.04370272 -0.001580297 -9.54622e-4 -0.03664439 -0.01434314 0.006547749 -0.0433495 -0.001580297 0.007699131 -0.0358392 -0.01434314 0.01623475 -0.04072451 -0.001580297 5.75898e-4 0.03099465 -0.01999998 -0.006944715 0.0302121 -0.01999998 -0.01405215 0.02763211 -0.01999998 -0.02032363 0.02340829 -0.01999998 -0.02538597 0.0177918 -0.01999998 -0.02893811 0.01111692 -0.01999998 -0.03076857 0.003780603 -0.01999998 -0.03076857 -0.003780603 -0.01999998 -0.02893811 -0.01111692 -0.01999998 -0.02538597 -0.0177918 -0.01999998 -0.02032363 -0.02340829 -0.01999998 -0.01405215 -0.02763211 -0.01999998 -0.006944715 -0.0302121 -0.01999998 5.75898e-4 -0.03099465 -0.01999998 0.01821929 -0.0449478 0.01580631 0.008099257 -0.04781889 0.01580631 0.02748221 -0.03996217 0.01580631 0.02748221 0.03996217 0.01580631 0.01821929 0.0449478 0.01580631 0.008099257 0.04781889 0.01580631 -0.002401709 0.04844045 0.01580631 -0.01278972 0.0467832 0.01580631 -0.02257609 0.04292511 0.01580631 -0.03130042 0.03704768 0.01580631 -0.03855222 0.0294274 0.01580631 -0.04399043 0.02042275 0.01580631 -0.04735916 0.01045733 0.01580631 -0.0485 0 0.01580631 -0.04735916 -0.01045733 0.01580631 -0.04399043 -0.02042275 0.01580631 -0.03855222 -0.0294274 0.01580631 -0.03130042 -0.03704768 0.01580631 -0.02257609 -0.04292511 0.01580631 -0.01278972 -0.0467832 0.01580631 -0.002401709 -0.04844045 0.01580631 -0.02884864 0.01134693 -0.02499997 -0.03073215 0.004066228 -0.02499997 0.008062243 0.02993321 -0.02499997 -0.02526736 0.01795989 -0.02499997 0.01494294 0.02716076 -0.02499997 -0.02019906 0.02351582 -0.02499997 0.02096796 0.02283293 -0.02499997 -0.01394206 0.02768784 -0.02499997 0.0257923 0.01719754 -0.02499997 -0.006864488 0.0302304 -0.02499997 6.17029e-4 0.03099381 -0.02499997 0.02913963 0.01057738 -0.02499997 0.03081828 0.003351509 -0.02499997 0.03073215 -0.004066228 -0.02499997 0.02888613 -0.01125121 -0.02499997 0.02538597 -0.0177918 -0.02499997 0.02043211 -0.02331364 -0.02499997 0.01430821 -0.02750039 -0.02499997 0.007364988 -0.03011238 -0.02499997 0 -0.03099995 -0.02499997 -0.007464826 -0.03008776 -0.02499997 -0.01449036 -0.02740484 -0.02499997 -0.02066314 -0.02310913 -0.02499997 -0.02561986 -0.01745337 -0.02499997 -0.02906876 -0.01077049 -0.02499997 -0.03080695 -0.003453731 -0.02499997 0.007985889 0.04783797 0.02810257 0.0180993 0.04499626 0.02810257 0.03534412 -0.033212 0.02810257 0.02736359 0.04004347 0.02810257 0.03534412 0.033212 0.02810257 0.02736359 -0.04004347 0.02810257 0.0180993 -0.04499626 0.02810257 0.007985889 -0.04783797 0.02810257 -0.002502202 -0.04843538 0.02810257 -0.01287293 -0.04676038 0.02810257 -0.02263969 -0.04289162 0.02810257 -0.03134429 -0.03701055 0.02810257 -0.03857839 -0.02939313 0.02810257 -0.04400253 -0.02039664 0.02810257 -0.04736226 -0.01044327 0.02810257 -0.0485 0 0.02810257 -0.04736226 0.01044327 0.02810257 -0.04400253 0.02039664 0.02810257 -0.03857839 0.02939313 0.02810257 -0.03134429 0.03701055 0.02810257 -0.02263969 0.04289162 0.02810257 -0.01287293 0.04676038 0.02810257 -0.002502202 0.04843538 0.02810257 0.0805 0.02678847 0.03234773 0.0805 0.01846313 0.03772413 0.0805 -0.03738808 -0.01913446 0.0805 0.02996265 -0.02943187 0.0805 -0.04083073 -0.009841144 0.0805 0.02223223 -0.0356332 0.0805 0.03602486 -0.02159184 0.0805 -0.04199999 0 0.0805 0.01326394 -0.03985053 0.0805 0.04008126 -0.01254957 0.0805 -0.04093796 0.009385168 0.0805 0.003557145 -0.04184907 0.0805 -0.03780561 0.0182957 0.0805 0.04190593 -0.00280857 0.0805 -0.03276133 0.02628099 0.0805 -0.006347715 -0.04151749 0.0805 -0.02606028 0.03293722 0.0805 -0.01804125 0.03792768 0.0805 0.04139745 0.00708872 0.0805 -0.01589912 -0.03887432 0.0805 0.03858399 0.01659137 0.0805 -0.02456533 -0.03406673 0.0805 0.0336222 0.02517026 0.0805 -0.03186374 -0.02736234 -0.0222494 0.04196679 0.02810257 -0.03075081 -0.03620266 0.02810257 0.04070067 -0.0244888 0.02810257 0.04501348 -0.01516681 0.02810257 -0.03781437 -0.02874577 0.02810257 -0.01270759 0.04576861 0.02810257 -0.0222494 -0.04196679 0.02810257 -0.04310983 -0.01994472 0.02810257 0.04722154 -0.005135595 0.02810257 -0.01270759 -0.04576861 0.02810257 -0.002571582 0.04743027 0.02810257 -0.04638946 -0.01021105 0.02810257 0.007684588 0.04687422 0.02810257 -0.002571582 -0.04743027 0.02810257 0.01758152 0.04412639 0.02810257 -0.04749995 0 0.02810257 0.007684588 -0.04687422 0.02810257 -0.04638946 0.01021105 0.02810257 0.02665632 0.03931522 0.02810257 0.04070067 0.0244888 0.02810257 0.04501348 0.01516681 0.02810257 0.01758152 -0.04412639 0.02810257 0.03448474 0.03266566 0.02810257 -0.04310983 0.01994472 0.02810257 0.04722154 0.005135595 0.02810257 0.02665632 -0.03931522 0.02810257 -0.03781437 0.02874577 0.02810257 0.03448474 -0.03266566 0.02810257 -0.03075081 0.03620266 0.02810257 0.01758152 0.04412639 0.03910255 0.02665632 0.03931522 0.03910255 0.007684588 0.04687422 0.03910255 -0.04638946 -0.01021105 0.03910255 -0.04749995 0 0.03910255 -0.002571582 0.04743027 0.03910255 -0.04310983 -0.01994472 0.03910255 -0.01270759 0.04576861 0.03910255 -0.03781437 -0.02874577 0.03910255 -0.0222494 0.04196679 0.03910255 -0.03075081 -0.03620266 0.03910255 -0.03075081 0.03620266 0.03910255 -0.0222494 -0.04196679 0.03910255 -0.03781437 0.02874577 0.03910255 -0.01270759 -0.04576861 0.03910255 -0.04310983 0.01994472 0.03910255 -0.002571582 -0.04743027 0.03910255 -0.04638946 0.01021105 0.03910255 0.007684588 -0.04687422 0.03910255 0.01758152 -0.04412639 0.03910255 0.02665632 -0.03931522 0.03910255 0.03448474 -0.03266566 0.03910255 0.04070067 -0.0244888 0.03910255 0.04501348 -0.01516681 0.03910255 0.04722154 -0.005135595 0.03910255 0.04722154 0.005135595 0.03910255 0.04501348 0.01516681 0.03910255 0.04070067 0.0244888 0.03910255 0.03448474 0.03266566 0.03910255 0.0213024 -0.03086185 0.03910255 0.01329767 -0.03506308 0.03910255 -0.03641027 0.008974313 0.03910255 -0.03320455 0.01742708 0.03910255 -0.03749996 0 0.03910255 0.004520118 -0.03722655 0.03910255 0.02806913 0.02486705 0.03910255 0.0213024 0.03086185 0.03910255 0.03320455 0.01742708 0.03910255 0.01329767 0.03506308 0.03910255 -0.004520118 -0.03722655 0.03910255 0.03641027 0.008974313 0.03910255 0.004520118 0.03722655 0.03910255 -0.03641027 -0.008974313 0.03910255 0.03749996 0 0.03910255 -0.01329767 -0.03506308 0.03910255 -0.03320455 -0.01742708 0.03910255 -0.004520118 0.03722655 0.03910255 -0.0213024 -0.03086185 0.03910255 -0.02806913 -0.02486705 0.03910255 0.03641027 -0.008974313 0.03910255 -0.01329767 0.03506308 0.03910255 0.03320455 -0.01742708 0.03910255 -0.0213024 0.03086185 0.03910255 0.02806913 -0.02486705 0.03910255 -0.02806913 0.02486705 0.03910255 -0.01627063 0.03378629 0.05299997 -0.008344531 0.03655976 0.05299997 -0.02338087 0.02931863 0.05299997 -0.03749996 0 0.05299997 -0.02931863 0.02338087 0.05299997 -0.03635251 -0.009205698 0.05299997 -0.03378629 0.01627063 0.05299997 -0.03298026 -0.01784801 0.05299997 -0.03655976 0.008344531 0.05299997 -0.02758961 -0.02539801 0.05299997 -0.02051055 -0.0313937 0.05299997 -0.01217621 -0.0354681 0.05299997 -0.003096699 -0.03737187 0.05299997 0.006172239 -0.03698849 0.05299997 0.01506358 -0.03434145 0.05299997 0.02303296 -0.02959275 0.05299997 0.02959275 -0.02303296 0.05299997 0.03434145 -0.01506358 0.05299997 0.03698849 -0.006172239 0.05299997 0.03737187 0.003096699 0.05299997 0.0354681 0.01217621 0.05299997 0.0313937 0.02051055 0.05299997 0.02539801 0.02758961 0.05299997 0.01784801 0.03298026 0.05299997 0.009205698 0.03635251 0.05299997 0 0.03749996 0.05299997 0.06810081 -0.01028728 0.0520001 0.07035636 -0.008288979 0.0520001 0.07206815 -0.005809009 0.0520001 0.06543254 -0.01168769 0.0520001 0.07313674 -0.002991437 0.0520001 0.06250667 -0.01240885 0.0520001 0.05949324 -0.01240885 0.0520001 0.05656743 -0.01168769 0.0520001 0.05389916 -0.01028728 0.0520001 0.05164361 -0.008288979 0.0520001 0.04993176 -0.005809009 0.0520001 0.04886323 -0.002991437 0.0520001 0.0805 0.003058195 0.04188847 0.0805 -0.003058195 0.04188847 0.09549999 0.002442061 0.04192888 0.09549999 0.01204574 0.04023551 0.09549999 -0.007293164 0.04136192 0.09549999 -0.04086786 -0.009685814 0.09549999 -0.04199999 0 0.09549999 -0.01663529 0.03856503 0.09549999 -0.03753256 -0.01884955 0.09549999 -0.02508062 0.03368914 0.09549999 -0.03217387 -0.02699702 0.09549999 -0.03217387 0.02699702 0.09549999 -0.02508062 -0.03368914 0.09549999 -0.03753256 0.01884955 0.09549999 -0.01663529 -0.03856503 0.09549999 -0.04086786 0.009685814 0.09549999 -0.007293164 -0.04136192 0.09549999 0.002442061 -0.04192888 0.09549999 0.01204574 -0.04023551 0.09549999 0.02099996 -0.03637301 0.09549999 0.02882212 -0.03054964 0.09549999 0.03509044 -0.02307933 0.09549999 0.03946703 -0.01436483 0.09549999 0.04171597 -0.004875898 0.09549999 0.04171597 0.004875898 0.09549999 0.03946703 0.01436483 0.09549999 0.03509044 0.02307933 0.09549999 0.02882212 0.03054964 0.09549999 0.02099996 0.03637301 0.09549999 -0.03252655 0.008017063 0.09549999 -0.02966272 0.01556819 0.09549999 0.0118792 -0.03132301 0.09549999 0.004037976 -0.03325569 0.09549999 -0.03349995 0 0.09549999 0.02507507 0.02221459 0.09549999 0.01903015 0.02756994 0.09549999 -0.004037976 -0.03325569 0.09549999 0.02966272 0.01556819 0.09549999 0.0118792 0.03132301 0.09549999 0.03252655 0.008017063 0.09549999 0.004037976 0.03325569 0.09549999 0.03349995 0 0.09549999 -0.0118792 -0.03132301 0.09549999 -0.004037976 0.03325569 0.09549999 -0.03252655 -0.008017063 0.09549999 -0.01903015 -0.02756994 0.09549999 0.03252655 -0.008017063 0.09549999 -0.02966272 -0.01556819 0.09549999 -0.02507507 -0.02221459 0.09549999 -0.0118792 0.03132301 0.09549999 0.02966272 -0.01556819 0.09549999 -0.01903015 0.02756994 0.09549999 0.02507507 -0.02221459 0.09549999 -0.02507507 0.02221459 0.09549999 0.01903015 -0.02756994 0.1088 0.004037976 0.03325569 0.1088 0.0118792 0.03132301 0.1088 -0.004037976 0.03325569 0.1088 -0.0118792 0.03132301 0.1088 -0.03252655 -0.008017063 0.1088 -0.03349995 0 0.1088 -0.01903015 0.02756994 0.1088 -0.02966272 -0.01556819 0.1088 -0.02507507 0.02221459 0.1088 -0.02507507 -0.02221459 0.1088 -0.02966272 0.01556819 0.1088 -0.01903015 -0.02756994 0.1088 -0.03252655 0.008017063 0.1088 -0.0118792 -0.03132301 0.1088 -0.004037976 -0.03325569 0.1088 0.004037976 -0.03325569 0.1088 0.0118792 -0.03132301 0.1088 0.01903015 -0.02756994 0.1088 0.02507507 -0.02221459 0.1088 0.02966272 -0.01556819 0.1088 0.03252655 -0.008017063 0.1088 0.03349995 0 0.1088 0.03252655 0.008017063 0.1088 0.02966272 0.01556819 0.1088 0.02507507 0.02221459 0.1088 0.01903015 0.02756994 0.05821847 0.01218658 0.05800008 0.05320638 0.009772837 0.05800008 0.05122709 0.007793605 0.05800008 0.05557644 0.01126205 0.05800008 0.0488134 0.00278151 0.05800008 0.04973787 0.005423545 0.05800008 0.06406855 0.0121175 0.05800008 0.06099998 0.01249998 0.05800008 0.04888248 -0.003068566 0.05800008 0.0485 0 0.05800008 0.05000656 -0.005949318 0.05800008 0.07146453 0.006836831 0.05800008 0.0669493 0.01099342 0.05800008 0.06946599 0.009196519 0.05800008 0.05694121 -0.0118227 0.05800008 0.07282269 0.004058718 0.05800008 0.05180341 -0.008466005 0.05800008 0.05416309 -0.01046454 0.05800008 0.07244718 -0.005021154 0.05800008 0.0733295 -0.002057373 0.05800008 0.0734573 0.001032233 0.05800008 0.06602114 -0.01144713 0.05800008 0.05996775 -0.01245731 0.05800008 0.06305742 -0.01232951 0.05800008 0.06867766 -0.009864211 0.05800008 0.07086426 -0.007677614 0.05800008 0.07089996 0.02507507 0.02221459 0.07089996 0.01903015 0.02756994 0.07049995 0.01903015 0.02756994 0.07049995 0.0118792 0.03132301 0.07089996 0.03252655 -0.008017063 0.07089996 0.03349995 0 0.07049995 0.03349995 0 0.07089996 0.02966272 0.01556819 0.07049995 0.02507507 0.02221459 0.07089996 0.02966272 -0.01556819 0.07049995 0.03252655 -0.008017063 0.07089996 0.03252655 0.008017063 0.07049995 0.02966272 0.01556819 0.07089996 0.02507507 -0.02221459 0.07049995 0.02966272 -0.01556819 0.07049995 0.03252655 0.008017063 0.07089996 0.01903015 -0.02756994 0.07049995 0.02507507 -0.02221459 0.07089996 0.0118792 -0.03132301 0.07049995 0.01903015 -0.02756994 0.07089996 0.004037976 -0.03325569 0.07049995 0.0118792 -0.03132301 0.07089996 -0.004037976 -0.03325569 0.07049995 0.004037976 -0.03325569 0.07089996 -0.0118792 -0.03132301 0.07049995 -0.004037976 -0.03325569 0.07089996 -0.01903015 -0.02756994 0.07049995 -0.0118792 -0.03132301 0.07089996 -0.02507507 -0.02221459 0.07049995 -0.01903015 -0.02756994 0.07089996 -0.02966272 -0.01556819 0.07049995 -0.02507507 -0.02221459 0.07049995 -0.02966272 -0.01556819 0.07089996 -0.03252655 -0.008017063 0.07049995 -0.03252655 -0.008017063 0.07089996 -0.03349995 0 0.07049995 -0.03349995 0 0.07089996 -0.03252655 0.008017063 0.07049995 -0.03252655 0.008017063 0.07089996 -0.02966272 0.01556819 0.07089996 -0.02507507 0.02221459 0.07049995 -0.02966272 0.01556819 0.07089996 -0.01903015 0.02756994 0.07049995 -0.02507507 0.02221459 0.07089996 -0.0118792 0.03132301 0.07049995 -0.01903015 0.02756994 0.07089996 -0.004037976 0.03325569 0.07049995 -0.0118792 0.03132301 0.07089996 0.004037976 0.03325569 0.07049995 -0.004037976 0.03325569 0.07089996 0.0118792 0.03132301 0.07049995 0.004037976 0.03325569 0.07049995 -0.02656364 -0.01394164 0.07049995 -0.02912825 -0.007179439 0.07049995 0.003616094 0.02978122 0.07049995 0.01063811 0.02805048 0.07049995 0.02245527 -0.01989364 0.07049995 0.01704192 -0.02468949 0.07049995 -0.02999997 0 0.07049995 0.02656364 -0.01394164 0.07049995 0.01063811 -0.02805048 0.07049995 -0.02912825 0.007179439 0.07049995 -0.003616094 0.02978122 0.07049995 0.02912825 -0.007179439 0.07049995 0.003616094 -0.02978122 0.07049995 -0.02656364 0.01394164 0.07049995 0.02999997 0 0.07049995 -0.003616094 -0.02978122 0.07049995 -0.01063811 0.02805048 0.07049995 0.02912825 0.007179439 0.07049995 -0.02245527 0.01989364 0.07049995 -0.01063811 -0.02805048 0.07049995 -0.01704192 0.02468949 0.07049995 0.02656364 0.01394164 0.07049995 -0.01704192 -0.02468949 0.07049995 0.02245527 0.01989364 0.07049995 -0.02245527 -0.01989364 0.07049995 0.01704192 0.02468949 0.07089996 0.02656364 0.01394164 0.07089996 0.02912825 0.007179439 0.07089996 -0.01063811 -0.02805048 0.07089996 -0.003616094 -0.02978122 0.07089996 -0.02245527 0.01989364 0.07089996 0.02999997 0 0.07089996 -0.01704192 0.02468949 0.07089996 0.003616094 -0.02978122 0.07089996 -0.02656364 0.01394164 0.07089996 -0.01063811 0.02805048 0.07089996 0.01063811 -0.02805048 0.07089996 -0.02912825 0.007179439 0.07089996 0.02912825 -0.007179439 0.07089996 -0.003616094 0.02978122 0.07089996 0.01704192 -0.02468949 0.07089996 -0.02999997 0 0.07089996 0.02656364 -0.01394164 0.07089996 0.02245527 -0.01989364 0.07089996 0.003616094 0.02978122 0.07089996 -0.02912825 -0.007179439 0.07089996 0.01063811 0.02805048 0.07089996 -0.02656364 -0.01394164 0.07089996 0.01704192 0.02468949 0.07089996 -0.02245527 -0.01989364 0.07089996 0.02245527 0.01989364 0.07089996 -0.01704192 -0.02468949 0.01132959 -0.02987372 0.01620256 0.01742708 -0.03320455 0.01620256 0.008974313 -0.03641027 0.01620256 0.003851115 -0.031717 0.01620256 -0.03506308 0.01329767 0.01620256 -0.03102153 0.007646083 0.01620256 -0.03722655 0.004520118 0.01620256 -0.03194993 0 0.01620256 0 -0.03749996 0.01620256 -0.003851115 -0.031717 0.01620256 0.02486705 0.02806913 0.01620256 0.03086185 0.0213024 0.01620256 0.02391487 0.0211867 0.01620256 0.01742708 0.03320455 0.01620256 0.01814961 0.02629429 0.01620256 0.03506308 0.01329767 0.01620256 0.02829027 0.01484787 0.01620256 -0.03722655 -0.004520118 0.01620256 -0.03102153 -0.007646083 0.01620256 0.008974313 0.03641027 0.01620256 0.01132959 0.02987372 0.01620256 0.03722655 0.004520118 0.01620256 0.03102153 0.007646083 0.01620256 -0.008974313 -0.03641027 0.01620256 0 0.03749996 0.01620256 0.003851115 0.031717 0.01620256 -0.01132959 -0.02987372 0.01620256 -0.03506308 -0.01329767 0.01620256 -0.02829027 -0.01484787 0.01620256 -0.01814961 -0.02629429 0.01620256 -0.01742708 -0.03320455 0.01620256 0.03722655 -0.004520118 0.01620256 0.03194993 0 0.01620256 -0.02391487 -0.0211867 0.01620256 -0.03086185 -0.0213024 0.01620256 -0.003851115 0.031717 0.01620256 -0.02486705 -0.02806913 0.01620256 -0.008974313 0.03641027 0.01620256 0.03102153 -0.007646083 0.01620256 0.03506308 -0.01329767 0.01620256 -0.01132959 0.02987372 0.01620256 -0.01742708 0.03320455 0.01620256 0.02829027 -0.01484787 0.01620256 0.03086185 -0.0213024 0.01620256 -0.01814961 0.02629429 0.01620256 -0.02486705 0.02806913 0.01620256 0.02391487 -0.0211867 0.01620256 -0.02391487 0.0211867 0.01620256 0.02486705 -0.02806913 0.01620256 0.01814961 -0.02629429 0.01620256 -0.03086185 0.0213024 0.01620256 -0.02829027 0.01484787 0.01620256 0 0.03194993 0.01610255 -0.007109522 0.03114891 0.01610255 -0.01386255 0.02878594 0.01610255 -0.03194993 0 0.01610255 -0.0309723 -0.007843255 0.01610255 -0.01992046 0.02497947 0.01610255 -0.02809917 -0.01520651 0.01610255 -0.02497947 0.01992046 0.01610255 -0.02350634 -0.0216391 0.01610255 -0.02878594 0.01386255 0.01610255 -0.01747494 -0.02674746 0.01610255 -0.03114891 0.007109522 0.01610255 -0.01037412 -0.03021883 0.01610255 -0.002638399 -0.03184086 0.01610255 0.005258738 -0.03151422 0.01610255 0.01283413 -0.0292589 0.01610255 0.01962405 -0.025213 0.01610255 0.025213 -0.01962405 0.01610255 0.0292589 -0.01283413 0.01610255 0.03151422 -0.005258738 0.01610255 0.03184086 0.002638399 0.01610255 0.03021883 0.01037412 0.01610255 0.02674746 0.01747494 0.01610255 0.0216391 0.02350634 0.01610255 0.01520651 0.02809917 0.01610255 0.007843255 0.0309723 0.01610255 0.03506308 -0.01329767 0.01610255 0.03086185 -0.0213024 0.01610255 0 -0.03749996 0.01610255 0.02486705 -0.02806913 0.01610255 -0.008974313 -0.03641027 0.01610255 0.01742708 -0.03320455 0.01610255 -0.01742708 -0.03320455 0.01610255 0.008974313 -0.03641027 0.01610255 -0.02486705 -0.02806913 0.01610255 -0.03086185 -0.0213024 0.01610255 -0.03506308 -0.01329767 0.01610255 -0.03722655 -0.004520118 0.01610255 -0.03722655 0.004520118 0.01610255 -0.03506308 0.01329767 0.01610255 -0.03086185 0.0213024 0.01610255 -0.02486705 0.02806913 0.01610255 -0.01742708 0.03320455 0.01610255 -0.008974313 0.03641027 0.01610255 0 0.03749996 0.01610255 0.008974313 0.03641027 0.01610255 0.01742708 0.03320455 0.01610255 0.02486705 0.02806913 0.01610255 0.03086185 0.0213024 0.01610255 0.03506308 0.01329767 0.01610255 0.03722655 0.004520118 0.01610255 0.03722655 -0.004520118 0.01610255 + + + + + + + + + + -5.92961e-6 0 1 0 0 1 2.31642e-6 0 1 1.30022e-6 0 1 -1.30022e-6 0 1 -2.31642e-6 0 1 -9.61509e-6 0 1 5.92959e-6 0 1 -9.12789e-7 0 1 0.0390684 0.8533796 -0.519824 0 0.8649297 -0.5018931 0.002515017 0.9375537 -0.3478317 -0.004654347 0.860859 -0.5088224 -0.002238333 0.9702526 -0.2420846 0.01638054 0.9497624 -0.3125429 0.00428617 0.9924144 -0.1228632 0.0284152 0.9944006 -0.1017851 -0.01741969 0.9993406 0.03186088 0.07196629 0.9909436 0.1133657 -0.1387559 0.8525404 -0.5039066 -0.0819956 0.8688587 -0.4882228 -0.1400889 0.940523 -0.3095024 -0.1188783 0.8693107 -0.479757 -0.1453495 0.9842379 -0.1007441 -0.1113851 0.9590549 -0.2603981 -0.1476601 0.9826289 0.1124143 -0.1077075 0.9940161 -0.018197 -0.1548351 0.9279954 0.3388963 -0.1068916 0.9684231 0.2252352 -0.1455114 0.8482296 0.5092477 -0.09077852 0.8854678 0.4557479 -0.111407 0.7761229 0.6206625 -0.1374772 0.6920148 0.7086718 -0.001162946 0.7503823 0.6610032 -0.01741975 -0.9993406 0.03186094 0.07196629 -0.9909436 0.1133657 -0.00651282 -0.9756678 -0.2191572 0.01356393 -0.993299 -0.1147744 0.0284152 -0.9944005 -0.1017851 0.03906828 -0.8533797 -0.519824 0.002660334 -0.9388063 -0.3444352 0.01615196 -0.9497661 -0.3125436 0 -0.8649297 -0.5018931 -0.004654347 -0.860859 -0.5088223 -0.1416978 -0.7132678 0.6864188 -0.1397903 -0.8067228 0.5741577 -0.05573326 -0.7492157 0.659977 -0.08648324 -0.8820484 0.4631537 -0.1548351 -0.9279954 0.3388963 -0.09892499 -0.8847771 0.4553938 -0.1476601 -0.9826289 0.1124143 -0.1068916 -0.9684231 0.2252352 -0.1453495 -0.9842379 -0.1007441 -0.1077075 -0.9940162 -0.01819694 -0.1400889 -0.940523 -0.3095024 -0.1113851 -0.959055 -0.2603981 -0.1387559 -0.8525404 -0.5039066 -0.1188783 -0.8693108 -0.479757 -0.08199578 -0.8688586 -0.4882228 -0.2830657 -0.7196928 0.6339686 -0.2493199 -0.6268331 0.738187 -0.2510319 -0.6664083 0.7020563 -0.244073 -0.6479212 0.7215446 -0.2428144 -0.6453518 0.7242668 -0.269467 -0.8562493 0.4407094 -0.278995 -0.7769886 0.5643141 -0.2397587 -0.7538515 0.6117383 -0.2657484 -0.9389809 0.218387 -0.2509488 -0.8864767 0.3888236 -0.2550911 -0.9479218 0.1907166 -0.2609088 -0.9652017 -0.01766955 -0.2600798 -0.9654596 -0.01569771 -0.2149223 -0.8514211 -0.4784252 -0.2663323 -0.9302032 -0.2525651 -0.2544681 -0.94138 -0.2214717 -0.2505419 -0.8734626 -0.4174829 -0.2757456 -0.8277224 -0.4887125 -0.2271718 -0.7254778 -0.6496731 -0.2997314 -0.7532811 -0.5854303 -0.2338641 -0.611838 -0.7556202 -0.2626667 -0.4998742 -0.8253072 -0.2494509 -0.6203849 -0.7435704 -0.2055709 -0.4523711 -0.8678139 0.01560759 0.7187884 -0.6950538 -0.01365888 0.78951 -0.6135858 0 -0.6652615 0.7466105 0.01538008 0.8579066 -0.5135753 -0.01318418 0.9021609 -0.4311982 -0.003426194 -0.8091114 0.5876453 0.003671824 -0.6706132 0.7417982 0.01465922 0.9521634 -0.3052377 -0.01221764 0.9733511 -0.2289941 -0.00636202 -0.9157628 0.401669 0.006852984 -0.8215944 0.5700314 0.01344615 0.9966292 -0.08092939 -0.01075798 0.99981 -0.01625561 -0.008806109 -0.9803169 0.1972341 0.009542465 -0.9295963 0.3684559 0.01174026 0.9889749 0.147618 -0.008806109 0.9803169 0.1972341 -0.01075798 -0.99981 -0.01625561 0.01174026 -0.9889749 0.147618 0.009542405 0.9295963 0.3684559 -0.00636202 0.9157628 0.401669 -0.01221764 -0.9733511 -0.2289941 0.01344615 -0.9966292 -0.08092939 0.006852924 0.8215944 0.5700315 -0.003426194 0.8091114 0.5876453 -0.01318418 -0.9021609 -0.4311982 0.01465922 -0.9521634 -0.3052377 0 0.6652615 0.7466105 0.003671824 0.6706131 0.7417983 -0.01365888 -0.78951 -0.6135858 0.01538008 -0.8579066 -0.5135753 -0.01364016 -0.6405772 -0.7677727 0.01560759 -0.7187883 -0.6950538 -0.01312887 -0.4622041 -0.8866764 0.0102359 -0.3571839 -0.933978 0.02011811 -0.3228117 -0.9462494 0.01534259 -0.5420819 -0.8401856 0.01310735 -0.3370323 -0.9414019 0.00100702 -0.1698247 -0.9854739 -5.05719e-4 -0.2512179 -0.9679304 0.02152609 -0.1143206 -0.9932107 -0.001944363 0.04036349 -0.9991832 0.002473056 -0.06516295 -0.9978716 0.02114063 0.1143215 -0.9932188 -0.003796815 0.2718737 -0.9623255 0.004425525 0.1508836 -0.9885417 0.01605325 0.3370177 -0.9413614 0.0102359 0.3571839 -0.933978 -0.01312887 0.4622041 -0.8866764 0.01534265 0.5420818 -0.8401857 -0.01364016 0.6405772 -0.7677727 -0.2055709 0.4523715 -0.8678138 -0.2685534 0.5046517 -0.8204913 -0.2149219 0.8514214 -0.4784248 -0.2484997 0.6265395 -0.7387125 -0.2415462 0.6216678 -0.7451072 -0.2324002 0.7369126 -0.6347835 -0.2717244 0.7598752 -0.5905552 -0.2757456 0.8277224 -0.4887125 -0.2663323 0.9302032 -0.2525651 -0.2505419 0.8734626 -0.4174828 -0.2609088 0.9652017 -0.01766955 -0.2544682 0.94138 -0.2214717 -0.2600799 0.9654595 -0.01569771 -0.2657484 0.9389809 0.218387 -0.2550912 0.9479218 0.1907166 -0.2830659 0.7196927 0.6339685 -0.269467 0.8562493 0.4407094 -0.2509487 0.8864768 0.3888235 -0.2397587 0.7538515 0.6117383 -0.244073 0.6479212 0.7215446 -0.2510319 0.6664083 0.7020563 -0.2789948 0.7769887 0.5643142 -0.2493199 0.6268331 0.738187 -0.2428145 0.6453518 0.7242666 -0.7193405 0 -0.6946578 -0.7193402 0 -0.694658 -0.7193401 0 -0.6946582 -0.7193393 0 -0.6946589 -0.7193396 0 -0.6946586 -0.7193397 0 -0.6946585 1.80039e-7 0 -1 0 0 -1 -8.88967e-7 0 -1 0 0 -1 -0.4547425 9.2454e-7 -0.890623 -0.4547775 1.53153e-6 -0.8906051 -0.4547534 -2.46153e-7 -0.8906174 -0.4547538 0 -0.8906172 -0.4547513 -2.76081e-7 -0.8906185 -0.4547485 0 -0.8906199 -0.5951657 1.06056e-5 -0.8036031 -0.5951673 0 -0.8036019 -0.5951657 -1.06056e-5 -0.8036031 -0.5951666 0 -0.8036023 -0.3907306 0 -0.9205052 -0.3907299 0 -0.9205054 -0.3907316 0 -0.9205046 -0.3907293 0 -0.9205057 0 -1 0 0 -1 5.35636e-7 0 -1 -1.36843e-7 0 1 0 0 1 2.67818e-7 0 1 -1.36843e-7 0.2881157 0.8399569 -0.45985 0.4219065 0.7833278 -0.4565006 0.3949481 0.7843049 -0.478416 0.302009 0.8052732 -0.5102213 0.08022826 0.8622205 -0.5001393 0.2297171 0.8477207 -0.4781211 -0.1251068 0.8575149 -0.4990156 0.03089123 0.877252 -0.4790351 -0.3237425 0.8046417 -0.4977374 -0.1693136 0.8607313 -0.4800778 -0.5045524 0.7064768 -0.4963037 -0.3603615 0.7990869 -0.4812484 -0.6573778 0.568429 -0.494715 -0.5322128 0.6956275 -0.4825475 -0.7736042 0.3981441 -0.4929684 -0.6758593 0.5558639 -0.4839727 -0.8466391 0.2050838 -0.4910629 -0.7837936 0.3872134 -0.485524 -0.8504083 0.1986035 -0.4871985 -0.8722858 0 -0.4889965 -0.8722858 0 -0.4889965 -0.8466391 -0.2050838 -0.4910629 -0.8504083 -0.1986036 -0.4871985 -0.7736042 -0.3981441 -0.4929684 -0.7837936 -0.3872133 -0.4855238 -0.6573778 -0.568429 -0.494715 -0.6758593 -0.5558639 -0.4839727 -0.5322127 -0.6956275 -0.4825476 -0.5045524 -0.7064768 -0.4963037 -0.3603614 -0.7990869 -0.4812484 -0.3237425 -0.8046417 -0.4977374 -0.1693136 -0.8607312 -0.4800779 -0.1251068 -0.8575149 -0.4990156 0.03089123 -0.8772519 -0.4790353 0.08022826 -0.8622205 -0.5001393 0.2882979 -0.8404878 -0.4587643 0.2297171 -0.8477208 -0.478121 0.3041145 -0.8039162 -0.51111 0.40019 -0.7830697 -0.4760776 0.4231025 -0.7855482 -0.451551 0.233273 0.6800716 -0.6950442 0.09804105 0.6915182 -0.7156749 -0.07240355 0.6958294 -0.7145483 0.06652247 0.7149237 -0.6960307 -0.2391337 0.6587884 -0.7133113 -0.1035057 0.7094553 -0.6971082 -0.3922726 0.582436 -0.7119625 -0.2671932 0.6640922 -0.6982761 -0.5227038 0.4711371 -0.7105003 -0.4153136 0.5815235 -0.6995321 -0.6226177 0.3313284 -0.7089209 -0.5395486 0.4665434 -0.7008742 -0.6859593 0.1711542 -0.7072242 -0.6329687 0.3257644 -0.7023021 -0.6904165 0.1672415 -0.7038149 -0.7088017 0 -0.7054079 -0.7088012 0 -0.7054084 -0.6859593 -0.1711542 -0.7072242 -0.6904166 -0.1672415 -0.7038148 -0.6226177 -0.3313284 -0.7089209 -0.6329686 -0.3257644 -0.7023022 -0.5227038 -0.4711371 -0.7105003 -0.5395486 -0.4665433 -0.7008742 -0.3922726 -0.582436 -0.7119625 -0.4153136 -0.5815235 -0.6995321 -0.2391337 -0.6587884 -0.7133113 -0.2671934 -0.6640923 -0.6982759 -0.07240355 -0.6958294 -0.7145483 -0.1035057 -0.7094553 -0.6971082 0.09804105 -0.6915182 -0.7156749 0.06652247 -0.7149238 -0.6960307 0.2332731 -0.6800714 -0.6950443 0.2638397 -0.9299722 -0.2560087 0.4777947 -0.8395853 -0.2584742 0.6001282 -0.7593297 -0.2515242 0.4550455 -0.8454404 -0.2795788 0.635818 -0.7381038 -0.2256954 0.464105 0.8616747 -0.2052402 0.635818 0.7381038 -0.2256953 0.6001282 0.7593297 -0.2515242 0.4550455 0.8454404 -0.2795788 0.4777947 0.8395853 -0.2584742 0.2524149 0.9314818 -0.2619705 0.2638398 0.9299722 -0.2560086 0.03393638 0.9637283 -0.2647191 0.05715954 0.9656873 -0.2533392 -0.1859982 0.9455495 -0.2670975 -0.152499 0.9558995 -0.2509985 -0.395932 0.8779636 -0.2691056 -0.35521 0.9010165 -0.2489883 -0.5849439 0.76455 -0.2707474 -0.5413677 0.8035914 -0.2473094 -0.7432131 0.6112594 -0.2720227 -0.7021486 0.6681982 -0.2459645 -0.86252 0.4261068 -0.2729328 -0.8299261 0.5012183 -0.244955 -0.9366737 0.2187505 -0.2734789 -0.9186363 0.3105387 -0.2442811 -0.9618263 0 -0.2736609 -0.9640696 0.105171 -0.2439444 -0.9640696 -0.105171 -0.2439444 -0.9366737 -0.2187505 -0.2734789 -0.9186362 -0.3105387 -0.2442812 -0.86252 -0.4261068 -0.2729328 -0.7432131 -0.6112594 -0.2720227 -0.8299261 -0.5012183 -0.244955 -0.7021486 -0.6681982 -0.2459646 -0.5849439 -0.76455 -0.2707474 -0.395932 -0.8779636 -0.2691056 -0.5413678 -0.8035914 -0.2473093 -0.1859982 -0.9455495 -0.2670975 -0.35521 -0.9010165 -0.2489882 0.03393638 -0.9637283 -0.2647191 -0.152499 -0.9558995 -0.2509985 0.2524149 -0.9314818 -0.2619705 0.05715948 -0.9656873 -0.2533394 0.464105 -0.8616746 -0.2052401 -0.8827703 0.469769 0.005825459 -0.9681135 0.2504451 -0.005792438 0.3140207 0.9494162 0 -0.7427879 0.669509 0.004880189 -0.8793221 0.476203 -0.004855215 0.4742932 0.8780598 0.0636956 0.3729661 0.9256223 -0.06418597 -0.5586159 0.8294172 0.003927528 -0.7387807 0.6739346 -0.00390321 0.6686847 0.7408182 0.06363314 -0.3412052 0.9399842 0.002960681 0.5822001 0.8105129 -0.06412553 -0.5547569 0.8320074 -0.00294578 0.8250609 0.5614576 0.06356054 -0.1034948 0.9946281 0.001984536 -0.3380852 0.9411134 -0.001975953 0.7580964 0.6489886 -0.06406056 0.1403726 0.9900982 9.98453e-4 0.9345307 0.3501743 0.06348651 -0.101516 0.9948335 -9.92264e-4 0.8905809 0.4503015 -0.06398707 0.1410297 0.9900054 0 0.9908705 0.118979 0.06340134 0.9720697 0.2258232 -0.06390821 0.990876 -0.1189799 0.06331348 0.9978942 -0.01158684 -0.06382095 0.9345466 -0.3501809 0.06321609 0.9665748 -0.2483385 -0.06372839 0.825084 -0.5614739 0.0631141 0.8799059 -0.4708687 -0.06362676 0.6687111 -0.7408481 0.0630058 0.7428473 -0.6664407 -0.06351965 0.4743177 -0.8781049 0.06288558 0.5632472 -0.823852 -0.06340831 0.3513928 -0.9340865 -0.06329011 0.3101302 -0.9506497 -0.009187221 0.1403549 -0.9899737 0.01589548 0.1196402 -0.9927359 -0.01271814 -0.1034863 -0.9945462 0.01298338 -0.1212879 -0.9925442 -0.01205718 -0.3411816 -0.9399192 0.0121268 -0.5585844 -0.8293714 0.01125782 -0.3567292 -0.9341409 -0.01119667 -0.7427563 -0.6694813 0.01038116 -0.5711804 -0.8207598 -0.01031988 -0.8827453 -0.4697561 0.009490787 -0.7520204 -0.6590724 -0.009438037 -0.9702184 -0.2420796 0.008590161 -0.8886049 -0.4585938 -0.008543252 -0.9999706 0 0.00767982 -0.9728945 -0.2311238 -0.007636725 -0.970232 0.242083 0.006759345 -0.9999279 0.009951829 -0.006718695 0.2705102 0.9627166 0.001001715 0.05908703 0.9982523 -0.001003503 0.7973271 -0.6008567 0.05692851 0.4714639 0.8818847 0.001125156 0.2729352 0.9620319 -0.001127243 0.77287 -0.6344444 0.01234692 0.6502961 0.7596799 0.001249551 0.6497428 -0.7590334 -0.04126518 0.4739447 0.8805538 -0.001250088 0.796044 0.5998908 0.08028101 0.6502531 -0.7548607 0.08576995 0.6712014 -0.7412734 0.001571893 0.7848689 0.6190031 0.02856814 0.6526575 0.757652 -0.001374304 0.4714639 -0.8818847 0.001125156 0.7583864 0.6518052 5.4872e-4 0.4739447 -0.8805538 -0.001250028 0.2705102 -0.9627166 0.001001715 0.2729353 -0.9620319 -0.001127064 0.05686742 -0.9983814 8.76898e-4 0.05908703 -0.9982523 -0.001003324 -0.1594442 -0.9872066 7.53429e-4 -0.1575422 -0.9875119 -8.78702e-4 -0.3682755 -0.9297165 6.28158e-4 -0.3667606 -0.9303151 -7.53827e-4 -0.5598294 -0.8286078 5.03789e-4 -0.5587236 -0.8293538 -6.30845e-4 -0.7251184 -0.6886242 3.78968e-4 -0.7244027 -0.689377 -5.05006e-4 -0.8563873 -0.5163339 2.5212e-4 -0.8560042 -0.5169687 -3.78634e-4 -0.947336 -0.3202415 -2.52946e-4 -0.947479 -0.3198183 1.2606e-4 -0.9941021 -0.1084482 -1.27045e-4 -0.9941183 0.1083002 0 -0.9941183 -0.1083002 0 -0.9941021 0.1084482 -1.27042e-4 -0.947479 0.3198183 1.2606e-4 -0.8563873 0.5163339 2.5212e-4 -0.947336 0.3202415 -2.52958e-4 -0.7251184 0.6886242 3.78968e-4 -0.8560042 0.5169687 -3.78678e-4 -0.5598294 0.8286078 5.03789e-4 -0.7244027 0.689377 -5.04904e-4 -0.3682755 0.9297165 6.28158e-4 -0.5587235 0.8293538 -6.30905e-4 -0.1594442 0.9872066 7.53429e-4 -0.3667606 0.9303151 -7.53756e-4 0.05686742 0.9983814 8.76898e-4 -0.1575422 0.9875119 -8.78407e-4 1 2.35731e-6 0 1 0 0 1 -5.47741e-6 0 1 -9.8889e-6 0 1 9.10262e-6 0 1 1.06716e-5 0 1 6.91687e-6 0 1 -4.06208e-6 0 1 -7.02131e-6 0 1 -1.64665e-5 0 1 1.07684e-5 0 1 -3.56186e-6 0 1 -2.61363e-6 0 1 5.27575e-6 0 1 1.08357e-5 0 1 1.39077e-6 0 1 -1.5629e-5 0 1 1.62704e-5 0 1 1.46418e-5 0 1 9.74275e-7 0 1 -3.82278e-6 0 1 -1.58849e-5 0 1 -1.87026e-6 0 1 9.71806e-6 0 3.51638e-7 0 1 -1.40391e-6 0 1 8.35767e-7 0 1 2.83394e-6 0 1 1.41165e-6 0 1 -3.52297e-7 0 1 1.87645e-6 0 1 -3.52956e-7 0 1 -3.52252e-7 0 1 -1.40382e-6 0 1 -3.54272e-7 0 1 -2.79734e-6 0 1 1.41973e-6 0 1 -3.32029e-6 0 1 -1 0 0 1.88564e-7 0 -1 -1.11302e-6 0 -1 0 0 -1 -2.90615e-7 0 -1 1.06852e-6 0 -1 0 0 -1 1.50483e-7 0 -1 0 0 -1 0 0 -1 0.4684087 0.8835119 0 0.468409 0.8835118 0 0.2675279 0.9635502 0 0.2675279 0.9635502 0 -0.9941382 -0.1081175 0 -0.9941381 -0.1081185 0 0.05413895 0.9985335 0 -0.9476532 -0.3193017 0 -0.9476532 -0.3193013 0 -0.1617819 0.9868266 0 -0.1617819 0.9868266 0 -0.8568566 -0.515555 0 -0.8568572 -0.515554 0 -0.370138 0.9289768 0 -0.3701376 0.928977 0 -0.7259957 -0.6876993 0 -0.5611876 -0.8276886 0 -0.7259956 -0.6876994 0 -0.5611876 0.8276886 0 -0.370138 -0.9289768 0 -0.7259957 0.6876993 0 -0.7259956 0.6876994 0 -0.1617819 -0.9868266 0 -0.3701376 -0.928977 0 -0.8568571 0.5155543 0 -0.8568567 0.5155548 0 -0.1617819 -0.9868266 0 -0.9476532 0.3193013 0 -0.9476532 0.3193017 0 0.05413895 -0.9985335 0 -0.9941381 0.1081185 0 -0.9941382 0.1081175 0 0.267528 -0.9635502 0 0.2675278 -0.9635502 0 0.4684089 -0.8835119 0 0.4684088 -0.883512 0 0.6473863 -0.7621622 0 0.7960927 -0.6051747 0 0.7960929 -0.6051746 0 0.9075758 -0.4198883 0 0.9075756 -0.419889 0 0.9766208 -0.2149696 0 0.9766204 -0.2149715 0 0.9766204 0.2149716 0 0.9766208 0.2149695 0 0.9075754 0.4198892 0 0.9075759 0.4198881 0 0.796093 0.6051744 0 0.7960926 0.6051748 0 0.6473863 0.7621622 0 -1.58522e-7 0 1 5.75233e-7 0 1 -3.2016e-7 0 1 -1.58986e-7 0 1 -5.71912e-7 0 1 -4.5457e-7 0 1 5.77981e-7 0 1 -5.82231e-7 0 1 4.6961e-7 0 1 -6.4032e-7 0 1 -5.80989e-7 0 1 3.13481e-7 0 1 1.56993e-7 0 1 -2.90495e-7 0 1 2.87617e-7 0 1 6.29795e-7 0 1 1.44783e-7 0 1 3.13683e-7 0 1 -2.90844e-7 0 1 -6.32445e-7 0 1 -1.62191e-7 0 1 -5.81688e-7 0 1 -4.28934e-7 0 1 3.14897e-7 0 1 -0.4646469 0.8853118 -0.01806354 -0.3302373 0.9437613 0.01605945 -0.6630367 0.7484148 -0.0160551 -0.5319761 0.8466361 0.01445245 -0.9927089 -0.1205368 0 -0.8229124 0.568014 -0.01324373 -0.7070555 0.7070555 0.01204252 -0.9350146 -0.3546036 -0.002014935 -0.9923186 -0.1236917 0.002067625 -0.9349728 0.3545889 -0.009630322 -0.8466912 0.5320115 0.008829295 -0.822978 -0.5680598 -0.00392121 -0.9315837 -0.3635047 0.004027307 -0.9926954 0.1205353 -0.005215823 -0.9438723 0.3302754 0.004814267 -0.9937124 0.1119631 0 -0.6631113 -0.7484989 -0.005717992 -0.8138346 -0.5810669 0.005879521 -0.4647104 -0.8854319 -0.007406592 -0.6462798 -0.7630625 0.007622361 -0.2393069 -0.9709025 -0.008987247 -0.4391781 -0.8983525 0.009256303 0 -0.9999454 -0.01045757 -0.2052031 -0.9786601 0.01078301 0.2392998 -0.9708738 -0.01181942 0.04132187 -0.9990715 0.01219904 0.4646834 -0.8853804 -0.01307374 0.2853101 -0.9583402 0.01350712 0.6630551 -0.7484355 -0.0142185 0.5118293 -0.8589614 0.01470613 0.8228887 -0.5679978 -0.01525425 0.7070187 -0.7070184 0.0157963 0.8589332 -0.511813 0.01677721 0.934894 -0.3545584 -0.01618117 0.9582781 -0.2852922 0.01764965 0.9925654 -0.1205195 -0.01699894 0.9989764 -0.04131811 0.01841282 0.9925532 0.1205179 -0.01770776 0.9785392 0.2051772 0.01906704 0.9348595 0.3545457 -0.01830774 0.8228389 0.5679638 -0.01879811 0.898218 0.4391127 0.01961237 0.6630002 0.7483735 -0.01917999 0.7629311 0.6461689 0.02004891 0.4646351 0.8852885 -0.01945275 0.580956 0.8136799 0.02037566 0.2392705 0.9707548 -0.01961618 0.3634305 0.9313938 0.02059364 0 0.9998066 -0.01967036 0.1236661 0.9921079 0.02070373 -0.2392721 0.9707614 -0.01926892 -0.1119481 0.993571 0.0168634 -2.5151e-6 0 1 -1.94086e-7 0 1 5.2976e-7 0 1 0 0 1 -1.87501e-6 0 1 -5.98626e-7 0 1 -1.30848e-6 0 1 5.85016e-7 0 1 1.37234e-6 0 1 -1.446e-6 0 1 2.75514e-6 0 1 3.13525e-7 0 1 -7.21568e-7 0 1 7.23019e-7 0 1 2.64734e-6 0 1 -9.48737e-6 0 1 -2.64733e-6 0 1 9.48734e-6 0 1 9.61499e-6 0 1 0.003299653 0.1452423 0.9893907 -0.002695679 0 0.9999964 0.01620811 0.1736249 0.9846786 -0.00627315 -0.1452403 0.9893766 0 -0.9932385 -0.1160921 0.01862668 -0.05813378 0.9981351 -0.001236259 -0.9930152 -0.1179805 -0.009688973 -0.3252761 0.9455695 -0.002432107 -0.9377237 -0.3473736 0.01162701 -0.286785 0.9579244 0.001215696 -0.9396914 -0.3420212 -0.008053183 -0.5283519 0.8489873 -0.003587603 -0.8302207 -0.5574233 0.01006668 -0.4999744 0.8659816 0.002391457 -0.8354856 -0.5495072 -0.006265521 -0.7047126 0.7094652 -0.004702329 -0.6764936 -0.7364336 0.008354127 -0.6862174 0.7273486 0.003527164 -0.686237 -0.7273694 -0.004328131 -0.8454374 0.5340571 -0.005777716 -0.4850993 -0.8744401 0.006491899 -0.83547 0.5494978 0.004622876 -0.4999947 -0.8660162 -0.002239704 -0.9434047 0.3316365 -0.00681293 -0.2667003 -0.9637555 0.004477977 -0.939683 0.3420172 0.005677402 -0.2867997 -0.9579738 0 -0.9936584 0.1124414 0.002313792 -0.9932358 0.1160926 -0.007807016 -0.03345376 -0.9994099 0.006691455 -0.05814254 -0.9982859 -0.008761525 0.2016522 -0.979418 0.007666587 0.1736426 -0.984779 -0.009674906 0.4255262 -0.9048945 0.00859946 0.3960651 -0.9181823 -0.01054799 0.6257038 -0.7799894 0.009493291 0.5971326 -0.8020865 0.01034671 0.7660029 -0.6427538 -0.01138126 0.7910403 -0.6116582 0.01115947 0.8935772 -0.4487708 -0.01217371 0.9123309 -0.4092727 0.01193177 0.9729753 -0.2306005 -0.01292556 0.9828213 -0.1841067 0.01266443 0.9999198 0 -0.01363754 0.9985898 0.05130821 0.01335567 0.9729582 0.2305951 -0.0143091 0.9587591 0.2838597 0.01400667 0.8935449 0.4487555 -0.01494026 0.8655478 0.5006035 0.01461768 0.765962 0.6427197 -0.01553028 0.7241464 0.6894714 0.01518839 0.5970904 0.8020302 -0.01608115 0.5424284 0.8399481 0.01571756 0.3960308 0.9181027 -0.01659035 0.3305142 0.9436553 1 -8.45759e-7 0 1 -1.65817e-6 0 1 4.24888e-7 0 1 -1.44921e-6 0 1 2.06313e-7 0 1 1.65496e-6 0 1 -6.18461e-7 0 1 -8.33272e-7 0 1 1.44146e-6 0 1 1.35137e-6 0 1 0 0 1 8.35872e-7 0 1 1.06473e-6 0 1 -1.68421e-6 0 1 -1.66654e-6 0 1 7.12431e-7 0 1 5.44518e-7 0 1 -1.81358e-7 0 0 0.2393161 0.9709418 0 -0.2393161 0.9709418 0 -0.2393162 0.9709418 0 -0.9927088 -0.1205374 0 -0.9927089 -0.1205369 0 -0.4647226 0.8854564 0 -0.4647225 0.8854564 0 -0.9350166 -0.3546039 0 -0.9350165 -0.3546043 0 -0.6631233 0.7485103 0 -0.6631227 0.7485108 0 -0.8229836 -0.5680653 0 -0.8229833 -0.5680657 0 -0.8229833 0.5680657 0 -0.8229836 0.5680653 0 -0.6631233 -0.7485103 0 -0.6631227 -0.7485108 0 -0.9350166 0.3546039 0 -0.9350165 0.3546043 0 -0.4647225 -0.8854564 0 -0.4647226 -0.8854564 0 -0.9927089 0.1205369 0 -0.9927088 0.1205374 0 -0.2393162 -0.9709418 0 -0.2393161 -0.9709418 0 0.2393161 -0.9709418 0 0.2393162 -0.9709418 0 0.4647226 -0.8854564 0 0.4647225 -0.8854564 0 0.6631233 -0.7485103 0 0.6631227 -0.7485108 0 0.8229836 -0.5680653 0 0.8229833 -0.5680657 0 0.9350165 -0.3546043 0 0.9350166 -0.3546039 0 0.9927088 -0.1205374 0 0.9927089 -0.1205369 0 0.9927089 0.1205369 0 0.9927088 0.1205374 0 0.9350166 0.3546039 0 0.9350165 0.3546043 0 0.8229836 0.5680653 0 0.8229833 0.5680657 0 0.6631233 0.7485103 0 0.6631227 0.7485108 0 0.4647225 0.8854564 0 0.4647226 0.8854564 0 0.2393162 0.9709418 1 5.07054e-6 0 1 -5.22231e-6 0 1 2.03746e-6 0 1 -8.14984e-7 0 1 2.53529e-6 0 1 -3.72924e-6 0 1 2.1673e-7 0 1 -2.23216e-7 0 1 2.53528e-6 0 1 -7.45844e-6 0 1 1.40825e-7 0 5.65896e-6 0 1 -8.34662e-6 0 1 1.79597e-6 0 1 -1.4368e-5 0 1 9.1279e-6 0 1 4.21879e-6 0 1 -6.19909e-6 0 1 -4.43051e-7 0 1 4.21877e-6 0 1 7.17517e-7 0 1 -1.53202e-6 0 1 7.37718e-7 0 1 -2.17446e-6 0 1 -5.42226e-7 0 1 1.23985e-5 0 1 -9.56585e-7 0 1 8.42135e-7 0 1 -8.43759e-6 0 1 2.47962e-5 0 1 0.1236772 0.9921938 0.01598614 0 0.9998847 -0.01518797 -0.2392895 0.9708343 -0.01487779 -0.1119551 0.993628 0.01302051 -0.992709 -0.1205362 0 -0.330254 0.9438107 0.01240003 -0.4646764 0.8853709 -0.01394772 -0.9350159 -0.3546026 -0.001554846 -0.9923191 -0.1236942 0.001597166 -0.6630734 0.7484517 -0.01239597 -0.5319996 0.8466712 0.01115953 -0.8229799 -0.5680626 -0.003026545 -0.931587 -0.3635055 0.00311017 -0.8229406 0.5680356 -0.01022523 -0.7070771 0.7070754 0.009297907 -0.6631179 -0.748502 -0.004415094 -0.8138407 -0.5810705 0.004538893 -0.9349901 0.3545961 -0.007435321 -0.8467031 0.5320222 0.00681734 -0.4647133 -0.8854428 -0.005717456 -0.9927014 0.1205319 -0.00402683 -0.6462874 -0.7630715 0.005886256 -0.9438762 0.3302788 0.003717243 -0.9937123 0.1119642 0 -0.239311 -0.9709182 -0.006938755 -0.4391878 -0.898367 0.007146179 0 -0.9999674 -0.008074641 -0.2052081 -0.9786829 0.008324682 0.2393061 -0.9709013 -0.009126067 0.04132348 -0.9991015 0.009418308 0.4646979 -0.8854119 -0.01009398 0.2853215 -0.9583751 0.01042836 0.6630856 -0.7484632 -0.01097756 0.5118522 -0.8589986 0.01135557 0.8229245 -0.5680288 -0.01177901 0.7070534 -0.707055 0.01219552 0.858982 -0.5118421 0.01295375 0.934943 -0.3545782 -0.0124945 0.9583393 -0.2853069 0.01362824 0.9926235 -0.1205258 -0.01312381 0.9990448 -0.04132241 0.01421791 0.9926161 0.1205248 -0.01367264 0.9786108 0.2051932 0.01472181 0.9349225 0.3545704 -0.01413625 0.8982886 0.4391452 0.01514345 0.8228969 0.5680054 -0.01451504 0.7629911 0.6462237 0.01547998 0.6630532 0.7484257 -0.01480931 0.5810036 0.8137489 0.01573449 0.4646691 0.885357 -0.01501923 0.3634625 0.9314731 0.01590216 0.2392901 0.97083 -0.01514577 0 -0.6631166 -0.7485162 0 -0.4647375 -0.8854485 0 -0.9927082 0.1205425 0 -0.822975 -0.5680776 0 -0.6631265 -0.7485073 0 -0.9350142 0.3546103 0 -0.9927092 0.120535 0 -0.9350142 -0.3546103 0 -0.822992 -0.5680531 0 -0.8229745 0.5680783 0 -0.9350187 0.3545984 0 -0.9927081 -0.1205437 0 -0.9350187 -0.3545984 0 -0.6631165 0.7485163 0 -0.9927092 -0.120534 0 -0.8229925 0.5680523 0 -0.4647093 0.8854633 0 -0.6631267 0.7485072 0 -0.2393172 0.9709415 0 -0.4647377 0.8854485 0 -0.2393172 0.9709414 0 0.2393172 0.9709414 0 0.4647095 0.8854633 0 0.2393172 0.9709415 0 0.6631166 0.7485162 0 0.4647375 0.8854485 0 0.822975 0.5680776 0 0.6631265 0.7485073 0 0.822992 0.5680531 0 0.9350142 0.3546103 0 0.9350187 0.3545984 0 0.9927081 0.1205437 0 0.9927092 0.120534 0 0.9927082 -0.1205425 0 0.9927092 -0.120535 0 0.9350142 -0.3546103 0 0.8229745 -0.5680783 0 0.9350187 -0.3545984 0 0.6631165 -0.7485163 0 0.8229925 -0.5680523 0 0.4647093 -0.8854633 0 0.6631267 -0.7485072 0 0.2393172 -0.9709415 0 0.4647377 -0.8854485 0 0.2393172 -0.9709414 0 -0.2393172 -0.9709414 0 -0.4647095 -0.8854633 0 -0.2393172 -0.9709415 1 -1.55581e-6 0 1 -2.31643e-6 0 1 2.07442e-6 0 1 -1.03721e-6 0 1 2.31643e-6 0 1 2.07441e-6 0 1 -1.15822e-6 0 1 5.18605e-7 0 1 1.15822e-6 0 1 0 0 1 -5.79107e-7 0 1 -5.18605e-7 0 1 -5.79109e-7 0 1 0 0 1 1.55581e-6 0 1 5.79109e-7 0 1 -1.73732e-6 0 1 1.03721e-6 0 1 2.31643e-6 0 1 -1.03721e-6 0 1 1.15822e-6 0 1 -5.79109e-7 0 1 -1.15821e-6 0 1 -1.03721e-6 0 1 -2.07442e-6 0 1 -2.07442e-6 0 1 1.15822e-6 0 1 1.03721e-6 0 1 1.03721e-6 0 1 2.07442e-6 0 -1 -5.18604e-7 0 -1 -1.03721e-6 0 -1 -2.89554e-6 0 -1 1.15822e-6 0 -1 -4.63286e-6 0 -1 0 0 -1 2.59302e-6 0 -1 -1.03721e-6 0 -1 -1.15822e-6 0 -1 2.07442e-6 0 -1 2.31643e-6 0 -1 -1.55581e-6 0 -1 0 0 -1 4.63286e-6 0 -1 1.03721e-6 0 -1 -5.79107e-7 0 -1 -8.68663e-7 0 -1 -5.79108e-7 0 -1 1.15822e-6 0 0 0.2393097 0.9709433 0 0.4647175 0.885459 0 0.2393193 0.970941 0 0.9927086 -0.120539 0 0.663115 0.7485176 0 0.4647333 0.8854507 0 0.9927091 -0.1205348 0 0.8229793 0.5680714 0 0.935015 -0.3546083 0 0.9350175 -0.3546016 0 0.935015 0.3546083 0 0.8229861 0.5680615 0 0.8229793 -0.5680714 0 0.8229861 -0.5680615 0 0.9927086 0.120539 0 0.9350175 0.3546016 0 0.663115 -0.7485176 0 0.9927091 0.1205348 0 0.6631265 -0.7485073 0 0.4647175 -0.885459 0 0.4647333 -0.8854507 0 0.2393097 -0.9709433 0 0.2393193 -0.970941 0 -0.2393098 -0.9709433 0 -0.2393193 -0.970941 0 -0.4647175 -0.885459 0 -0.4647333 -0.8854507 0 -0.6631153 -0.7485173 0 -0.6631262 -0.7485076 0 -0.8229858 -0.568062 0 -0.8229796 -0.568071 0 -0.9350175 -0.3546016 0 -0.935015 -0.3546083 0 -0.9927092 -0.1205342 0 -0.9927085 -0.1205396 0 -0.9927085 0.1205396 0 -0.9927092 0.1205342 0 -0.935015 0.3546083 0 -0.8229796 0.568071 0 -0.9350175 0.3546016 0 -0.6631153 0.7485173 0 -0.8229858 0.568062 0 -0.4647175 0.885459 0 -0.6631262 0.7485076 0 -0.2393098 0.9709433 0 -0.4647333 0.8854507 0 -0.2393193 0.970941 -1.5253e-7 0 -1 3.267e-7 0 -1 -1.5253e-7 0 -1 0 0 -1 1.42997e-7 0 -1 0 0 -1 -3.267e-7 0 -1 3.26701e-7 0 -1 -1.6335e-7 0 -1 -1.5253e-7 0 -1 1.6335e-7 0 -1 1.5253e-7 0 -1 0 0 -1 1.6335e-7 0 -1 -3.05061e-7 0 -1 -1.6335e-7 0 -1 1.5253e-7 0 -1 -1.7356e-7 0 -1 2.45025e-7 0 -1 1.6335e-7 0 -1 -1.6335e-7 0 -1 1.5253e-7 0 -1 0 0 -1 1.7356e-7 0 -1 -2.45025e-7 0 -1 -1.42997e-7 0 -1 -3.26701e-7 0 -1 0 0.3944658 0.9189107 -0.05013191 0.4449262 -0.8941631 -0.09605282 0.3897098 0.9159149 -0.1537171 0.4392797 -0.8851014 -0.9927085 -0.1205407 0 -0.9638395 -0.1201429 -0.2378639 -0.1967986 0.374978 0.9059039 -0.2684159 0.4271583 -0.8634169 -0.8408562 -0.3280951 -0.4304816 -0.9094994 -0.3449367 0.2320123 -0.3086879 0.3484429 0.885042 -0.4059889 0.4059802 -0.818751 -0.6679097 -0.4768744 -0.571391 -0.7464618 -0.5152564 0.421077 -0.4424634 0.3054192 0.8431757 -0.5852657 0.3677346 -0.7226585 -0.479776 -0.5664549 -0.6700327 -0.8199868 0.2869223 -0.495275 -0.549119 -0.6198333 0.5606025 -0.6164863 0.2338053 0.751851 -0.9937126 0.1119622 0 -0.8446326 0.1025602 0.5254306 -0.2960113 -0.6054924 -0.7387533 -0.3494018 -0.6657418 0.6593226 -0.1265401 -0.6034777 -0.7872753 -0.163888 -0.6649305 0.7287032 0.02352112 -0.5686635 -0.8222339 0 -0.6282643 0.778 0.1512572 -0.5080701 -0.8479306 0.139124 -0.5644544 0.8136559 0.2548937 -0.4277555 -0.8672108 0.252151 -0.4804413 0.8399977 0.3333652 -0.3333548 -0.881897 0.3386358 -0.382245 0.859776 0.398594 -0.2751375 0.8748841 0.3862175 -0.2301306 -0.8932392 0.4325947 -0.1640636 0.8865354 0.4136263 -0.1231423 -0.9020806 0.4416477 -0.05362802 0.8955845 0.4164925 -0.01722598 -0.9089759 0.4272848 0.05188351 0.9026272 0.3963012 0.08309507 -0.9143525 0.3916156 0.1485233 0.9080628 0.3552655 0.1736736 -0.91849 0.337217 0.2327708 0.9121965 0.2961878 0.2508539 -0.9215992 0.2671969 0.3016059 0.9152266 0.2224519 0.3115578 -0.9238219 0.1850441 0.3525777 0.9173046 0.1379013 0.3534041 -0.9252508 0.09462219 0.3838942 0.9185162 0.04671132 0.3747365 -0.9259539 -0.8854556 0.4647241 0 -0.8854553 0.4647245 0 -0.7485075 0.6631264 0 0.1205371 0.9927089 0 -0.7485146 0.6631184 0 -0.5680595 0.8229875 0 0.3545981 0.9350188 0 -0.3545981 0.9350188 0 -0.5680707 0.8229798 0 0.5680598 0.8229873 0 0.3546121 0.9350136 0 -0.3546122 0.9350136 0 -0.1205371 0.9927089 0 0.7485075 0.6631264 0 0.5680704 0.82298 0 0.8854553 0.4647245 0 0.7485146 0.6631184 0 0.9709393 0.2393257 0 0.8854556 0.4647241 0 0.970943 0.2393107 0 0.9709393 -0.2393257 0 0.8854556 -0.4647241 0 0.970943 -0.2393107 0 0.7485075 -0.6631264 0 0.8854553 -0.4647245 0 0.5680595 -0.8229875 0 0.7485146 -0.6631184 0 0.5680707 -0.8229798 0 0.3545981 -0.9350188 0 0.3546122 -0.9350136 0 0.1205371 -0.9927089 0 -0.1205371 -0.9927089 0 -0.3545981 -0.9350188 0 -0.3546121 -0.9350136 0 -0.5680598 -0.8229873 0 -0.5680704 -0.82298 0 -0.7485075 -0.6631264 0 -0.7485146 -0.6631184 0 -0.8854553 -0.4647245 0 -0.8854556 -0.4647241 0 -0.9709393 -0.2393257 0 -0.970943 -0.2393107 0 -0.9709393 0.2393257 0 -0.970943 0.2393107 0 3.64374e-7 0 1 -5.99555e-7 0 1 3.04911e-7 0 1 0 0 1 9.15071e-7 0 1 -3.17777e-7 0 1 -3.32559e-7 0 1 -5.95832e-7 0 1 -1.63332e-7 0 1 -6.35388e-7 0 1 3.27986e-7 0 1 0 0 1 6.09572e-7 0 1 1.51345e-7 0 1 6.01444e-7 0 1 -6.01218e-7 0 1 -5.96674e-7 0 1 + + + + + + + + + + + + + + +

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

+
+
+
+
+ + + + + 0.6859207 -0.3240135 0.6515582 7.481132 0.7276763 0.3054208 -0.6141704 -6.50764 0 0.8953956 0.4452714 5.343665 0 0 0 1 + + + + -0.2908646 -0.7711008 0.5663932 4.076245 0.9551712 -0.1998834 0.2183912 1.005454 -0.05518906 0.6045247 0.7946723 5.903862 0 0 0 1 + + + + 1 0 0 0 0 1 0 0 0 0 1 0 0 0 0 1 + + + + + + + + + + + + + +
\ No newline at end of file diff --git a/kuka_kr5_support/meshes/kr5_arc/visual/link_6.dae b/kuka_kr5_support/meshes/kr5_arc/visual/link_6.dae new file mode 100644 index 000000000..b006c26ed --- /dev/null +++ b/kuka_kr5_support/meshes/kr5_arc/visual/link_6.dae @@ -0,0 +1,201 @@ + + + + + Blender User + Blender 2.79.0 commit date:2017-09-11, commit time:10:43, hash:5bd8ac9abfa + + 2017-11-10T20:10:26 + 2017-11-10T20:10:26 + + Z_UP + + + + + + + 49.13434 + 1.777778 + 0.1 + 100 + + + + + + 0 + 0 + 0 + + + + + + + + + 1 1 1 + 1 + 0 + 0.00111109 + + + + + 0 + 0 + 8192 + 1 + 1 + 1 + 1 + 0 + 0 + 0 + 1 + 29.99998 + 75 + 0.15 + 1 + 0 + 1 + 2 + 1.000799 + 30.002 + 1 + 3 + 0.04999995 + 2880 + 3 + 1 + 0 + 0 + 2 + 1 + 1 + 1 + 0 + 1 + 0.1 + 0.1 + 1 + 0.000999987 + 1 + 0 + 0 + 1 + 1 + 1 + 1 + 1 + 1 + 1 + 2 + 1 + 1 + 1 + 1 + 0 + + + + + + + + + + + + 0 0 0 1 + + + 0 0 0 1 + + + 0.4 0.4 0.4 1 + + + 0.5 0.5 0.5 1 + + + 0 + + + 1 1 1 1 + + + 1 + + + + + + + + + + + + + + + + 0.01197487 -0.00358504 -0.115 0.01126205 -0.005423545 -0.1088 0.01218658 -0.00278151 -0.1088 0.01231008 0.002170562 -0.115 0.01247882 -7.2681e-4 -0.115 0.01249998 0 -0.1088 0.01147764 0.00495094 -0.115 0.01218658 0.00278151 -0.1088 0 0.01249998 -0.115 0 0.01249998 -0.1088 -0.00278151 0.01218658 -0.1088 -0.002882659 0.01216304 -0.115 0.01002651 0.007464468 -0.115 0.01126205 0.005423545 -0.1088 -0.005609989 0.01117038 -0.115 -0.005423545 0.01126205 -0.1088 0.008034825 0.009575545 -0.115 0.009772837 0.007793605 -0.1088 -0.008034825 0.009575545 -0.115 -0.007793605 0.009772837 -0.1088 0.005609989 0.01117038 -0.115 0.007793605 0.009772837 -0.1088 -0.01002651 0.007464468 -0.115 -0.009772837 0.007793605 -0.1088 0.002882659 0.01216304 -0.115 0.005423545 0.01126205 -0.1088 0.00278151 0.01218658 -0.1088 -0.01147764 0.00495094 -0.115 -0.01126205 0.005423545 -0.1088 -0.01231008 0.002170562 -0.115 -0.01218658 0.00278151 -0.1088 -0.01247882 -7.2681e-4 -0.115 -0.01249998 0 -0.1088 -0.01197487 -0.00358504 -0.115 -0.01218658 -0.00278151 -0.1088 -0.01082527 -0.006249964 -0.115 -0.01126205 -0.005423545 -0.1088 -0.009092152 -0.008578002 -0.115 -0.009772837 -0.007793605 -0.1088 -0.007793605 -0.009772837 -0.1088 -0.006868839 -0.01044356 -0.115 -0.005423545 -0.01126205 -0.1088 -0.004275202 -0.0117461 -0.115 -0.00278151 -0.01218658 -0.1088 -0.001451134 -0.01241546 -0.115 0 -0.01249998 -0.1088 0.001451134 -0.01241546 -0.115 0.00278151 -0.01218658 -0.1088 0.004275202 -0.0117461 -0.115 0.005423545 -0.01126205 -0.1088 0.006868839 -0.01044356 -0.115 0.007793605 -0.009772837 -0.1088 0.009092152 -0.008578002 -0.115 0.009772837 -0.007793605 -0.1088 0.01082527 -0.006249964 -0.115 0.002946734 -0.01934123 -0.115 0.002915322 -0.0207861 -0.115 0.002946734 -0.02065873 -0.1088 0.002915322 -0.01921385 -0.1088 -2.98735e-4 -0.01699531 -0.115 2.98735e-4 -0.01699531 -0.1088 0.002303063 -0.01804727 -0.115 -0.001660823 -0.01747828 -0.115 -0.001131772 -0.01720064 -0.1088 0.002468943 -0.01829576 -0.1088 0.001131772 -0.01720064 -0.115 0.001660823 -0.01747828 -0.1088 -0.002468943 -0.01829576 -0.115 -0.002303063 -0.01804727 -0.1088 -0.00293976 -0.01927542 -0.115 -0.002924978 -0.01927906 -0.1088 -0.002915322 -0.0207861 -0.115 -0.002946734 -0.02065873 -0.1088 -0.002254903 -0.02199763 -0.115 -0.002468943 -0.02170419 -0.1088 -0.001131772 -0.02279931 -0.115 -0.001660823 -0.02252161 -0.1088 -2.9874e-4 -0.02300465 -0.1088 2.9874e-4 -0.02300465 -0.115 0.001131772 -0.02279931 -0.1088 0.001660823 -0.02252161 -0.115 0.002303063 -0.02195268 -0.1088 0.002468943 -0.02170419 -0.115 -0.02180761 0.01099514 -0.115 -0.01708883 0.01348334 -0.115 -0.01661103 0.01243793 -0.115 -0.01591092 0.01169496 -0.115 0.01680958 0.01554214 -0.115 0.01591092 0.01658928 -0.115 0.01689893 0.01763206 -0.115 0.008136153 -0.02302753 -0.115 0.01183903 -0.0160948 -0.115 0.01191079 -0.02132129 -0.115 0.01963573 0.01452249 -0.115 0.01457107 0.01713097 -0.115 0.01367604 0.0202344 -0.115 0.01119536 -0.01480084 -0.115 0.01716089 0.01420772 -0.115 -0.02335208 0.007151484 -0.115 0.01313298 0.01698797 -0.115 0.01694715 0.01307827 -0.115 0.02180761 0.01099514 -0.115 0.01005971 0.02225458 -0.115 0.01661103 0.01243793 -0.115 0.01192599 0.01619297 -0.115 0.01580297 0.01162046 -0.115 0.02335208 0.007151484 -0.115 0.004127442 -0.02407133 -0.115 -0.02422481 0.003102064 -0.115 0.002254903 0.02199763 -0.115 0.002071142 0.02433466 -0.115 0.006153941 0.02363455 -0.115 0.001131772 0.02279931 -0.115 0.002915322 0.0207861 -0.115 -2.9874e-4 0.02300465 -0.115 -0.01147466 -0.0127421 -0.115 0.002978086 0.01963835 -0.115 -0.01237326 -0.01169496 -0.115 -0.002071142 0.02433466 -0.115 0.002804994 0.01893615 -0.115 0.01122677 0.01492822 -0.115 -0.001660823 0.02252161 -0.115 0 -0.02442264 -0.115 0.002468943 0.01829576 -0.115 -0.01342415 -0.01122927 -0.115 -0.01112335 -0.01407653 -0.115 -0.002468943 0.02170419 -0.115 -0.01444089 -0.01113748 -0.115 -0.02440059 -0.001036524 -0.115 -0.01133704 -0.01520591 -0.115 0.01119536 0.01348334 -0.115 0.01167315 0.01243793 -0.115 0.01237326 0.01169496 -0.115 -0.01580297 -0.01162046 -0.115 -0.01192599 -0.01619297 -0.115 0.01342415 0.01122927 -0.115 0.01444089 0.01113748 -0.115 -0.004127442 -0.02407133 -0.115 -0.006153941 0.02363455 -0.115 -0.002915322 0.0207861 -0.115 -0.02387446 -0.005145311 -0.115 -0.002946734 0.01934123 -0.115 -0.008136153 -0.02302753 -0.115 -0.0226615 -0.009106099 -0.115 2.98735e-4 0.01699531 -0.115 0.001660823 0.01747828 -0.115 0.02422481 0.003102064 -0.115 -0.001131772 0.01720064 -0.115 -0.01191079 -0.02132129 -0.115 -0.01313298 -0.01698797 -0.115 -0.01005971 0.02225458 -0.115 -0.02079659 -0.01280492 -0.115 -0.0167846 -0.01268112 -0.115 0.02440059 -0.001036524 -0.115 -0.01712024 -0.01378053 -0.115 0.02387446 -0.005145311 -0.115 -0.01708883 -0.01480084 -0.115 -0.002303063 0.01804727 -0.115 -0.01534277 -0.01900166 -0.115 -0.01457107 -0.01713097 -0.115 -0.01591092 -0.01658928 -0.115 0.0226615 -0.009106099 -0.115 -0.01833337 -0.01613539 -0.115 -0.01661103 -0.01584631 -0.115 0.01591092 -0.01169496 -0.115 0.02079659 -0.01280492 -0.115 0.01680958 -0.0127421 -0.115 -0.01147466 0.01554214 -0.115 -0.01215273 0.01638764 -0.115 -0.01301032 0.01694142 -0.115 -0.01367604 0.0202344 -0.115 0.01457113 -0.01115328 -0.115 0.01716089 -0.01407653 -0.115 -0.01112335 0.01420772 -0.115 -0.01444083 0.01714676 -0.115 0.01833337 -0.01613539 -0.115 0.01313298 -0.01129627 -0.115 0.01694715 -0.01520591 -0.115 -0.01133704 0.01307827 -0.115 0.01661103 -0.01584631 -0.115 -0.01192599 0.01209121 -0.115 -0.01689893 0.01763206 -0.115 -0.01580297 0.01666378 -0.115 0.01192599 -0.01209121 -0.115 0.01580297 -0.01666378 -0.115 -0.0167846 0.01560312 -0.115 -0.01313298 0.01129627 -0.115 -0.01457113 0.01115328 -0.115 0.01122677 -0.01335602 -0.115 0.01534277 -0.01900166 -0.115 0.01301032 -0.01694142 -0.115 0.01444083 -0.01714676 -0.115 -0.01963573 0.01452249 -0.115 -0.01712024 0.01450371 -0.115 -0.01189863 0.02198684 -0.114 -0.008117437 0.0236454 -0.114 -0.01535528 0.01972848 -0.114 0.004114806 -0.02465897 -0.114 0 -0.02499997 -0.114 -0.01839309 0.01693201 -0.114 -0.02092915 0.01367366 -0.114 0.008117437 -0.0236454 -0.114 -0.02289432 0.01004236 -0.114 0.01189863 -0.02198684 -0.114 -0.02423501 0.006137132 -0.114 0.01535528 -0.01972848 -0.114 -0.02491456 0.002064466 -0.114 0.01839309 -0.01693201 -0.114 -0.02491456 -0.002064466 -0.114 0.02092915 -0.01367366 -0.114 -0.02423501 -0.006137132 -0.114 -0.02289432 -0.01004236 -0.114 0.02289432 -0.01004236 -0.114 -0.02092915 -0.01367366 -0.114 0.02423501 -0.006137132 -0.114 -0.01839309 -0.01693201 -0.114 0.02491456 -0.002064466 -0.114 -0.01535528 -0.01972848 -0.114 0.02491456 0.002064466 -0.114 0.02423501 0.006137132 -0.114 -0.01189863 -0.02198684 -0.114 0.02289432 0.01004236 -0.114 -0.008117437 -0.0236454 -0.114 0.02092915 0.01367366 -0.114 -0.004114806 -0.02465897 -0.114 0.01839309 0.01693201 -0.114 0.01535528 0.01972848 -0.114 0.01189863 0.02198684 -0.114 0.008117437 0.0236454 -0.114 0.004114806 0.02465897 -0.114 0 0.02499997 -0.114 -0.004114806 0.02465897 -0.114 0.004114806 0.02465897 -0.1088 0.008117437 0.0236454 -0.1088 0 -0.02499997 -0.1088 -0.004114806 -0.02465897 -0.1088 0.01189863 0.02198684 -0.1088 -0.008117437 -0.0236454 -0.1088 0.01535528 0.01972848 -0.1088 -0.01189863 -0.02198684 -0.1088 0.01839309 0.01693201 -0.1088 -0.01535528 -0.01972848 -0.1088 0.02092915 0.01367366 -0.1088 -0.01839309 -0.01693201 -0.1088 0.02289432 0.01004236 -0.1088 -0.02092915 -0.01367366 -0.1088 0.02423501 0.006137132 -0.1088 -0.02289432 -0.01004236 -0.1088 0.02491456 0.002064466 -0.1088 -0.02423501 -0.006137132 -0.1088 0.02491456 -0.002064466 -0.1088 -0.02491456 -0.002064466 -0.1088 -0.02491456 0.002064466 -0.1088 0.02423501 -0.006137132 -0.1088 -0.02423501 0.006137132 -0.1088 0.02289432 -0.01004236 -0.1088 -0.02289432 0.01004236 -0.1088 0.02092915 -0.01367366 -0.1088 0.01839309 -0.01693201 -0.1088 -0.02092915 0.01367366 -0.1088 0.01535528 -0.01972848 -0.1088 -0.01839309 0.01693201 -0.1088 0.01189863 -0.02198684 -0.1088 -0.01535528 0.01972848 -0.1088 0.008117437 -0.0236454 -0.1088 0.004114806 -0.02465897 -0.1088 -0.01189863 0.02198684 -0.1088 -0.008117437 0.0236454 -0.1088 -0.004114806 0.02465897 -0.1088 0 0.02499997 -0.1088 -0.01313298 0.01698797 -0.1088 -0.01215273 0.01638764 -0.1088 -0.01167315 0.01584631 -0.1088 0.01580297 -0.01162046 -0.1088 0.01661103 -0.01243793 -0.1088 -0.01580297 -0.01666378 -0.1088 -0.0167846 -0.01560312 -0.1088 -0.01444083 -0.01714676 -0.1088 -0.002468943 0.01829576 -0.1088 -0.001660823 0.01747828 -0.1088 -0.01119536 0.01480084 -0.1088 -0.01712024 -0.01450371 -0.1088 -0.002915322 0.01921385 -0.1088 -2.98735e-4 0.01699531 -0.1088 -0.01708883 -0.01348334 -0.1088 -0.01301032 -0.01694142 -0.1088 -0.002946734 0.02065873 -0.1088 -0.01661103 -0.01243793 -0.1088 0.001131772 0.01720064 -0.1088 -0.01183903 -0.0160948 -0.1088 -0.01591092 -0.01169496 -0.1088 0.002303063 0.01804727 -0.1088 -0.002303063 0.02195268 -0.1088 -0.001131772 0.02279931 -0.1088 0.01192599 0.01209121 -0.1088 0.01313298 0.01129627 -0.1088 -0.01121711 -0.01486301 -0.1088 0.01122677 0.01335602 -0.1088 2.9874e-4 0.02300465 -0.1088 0.001660823 0.02252161 -0.1088 0.01457113 0.01115328 -0.1088 0.01119536 0.01480084 -0.1088 0.002924978 0.01927906 -0.1088 -0.01215273 -0.01189655 -0.1088 -0.01167315 -0.01243793 -0.1088 -0.01119536 -0.01348334 -0.1088 0.01591092 0.01169496 -0.1088 -0.01313298 -0.01129627 -0.1088 0.01183903 0.0160948 -0.1088 0.002468943 0.02170419 -0.1088 0.002946734 0.02065873 -0.1088 -0.01457113 -0.01115328 -0.1088 0.01661103 0.01243793 -0.1088 0.01301032 0.01694142 -0.1088 0.01708883 0.01480084 -0.1088 0.01706707 0.01342117 -0.1088 0.01444083 0.01714676 -0.1088 0.01580297 0.01666378 -0.1088 0.01661103 0.01584631 -0.1088 -0.0167846 0.01268112 -0.1088 -0.01580297 0.01162046 -0.1088 0.01192599 -0.01619297 -0.1088 0.01313298 -0.01698797 -0.1088 0.01122677 -0.01492822 -0.1088 -0.01444089 0.01113748 -0.1088 -0.01712024 0.01378053 -0.1088 0.01457107 -0.01713097 -0.1088 -0.01708883 0.01480084 -0.1088 0.01119536 -0.01348334 -0.1088 -0.01342415 0.01122927 -0.1088 -0.01237326 0.01169496 -0.1088 0.01591092 -0.01658928 -0.1088 -0.01661103 0.01584631 -0.1088 0.01167315 -0.01243793 -0.1088 -0.01591092 0.01658928 -0.1088 0.01237326 -0.01169496 -0.1088 0.01661103 -0.01584631 -0.1088 0.01706707 -0.01486301 -0.1088 -0.01121711 0.01342117 -0.1088 -0.01167315 0.01243793 -0.1088 0.01342415 -0.01122927 -0.1088 -0.01457107 0.01713097 -0.1088 0.01444089 -0.01113748 -0.1088 0.01708883 -0.01348334 -0.1088 + + + + + + + + + + -0.9438307 0.3302604 -0.0105704 -0.9982562 -0.05814009 0.01022094 -0.9936652 0.1119593 -0.009734928 -0.9579488 -0.2867929 0.009176969 -0.9936742 -0.1119591 -0.008761465 0.1119641 -0.9937123 0 0.116093 -0.9932366 0.001876533 -0.8659976 -0.4999845 0.007994651 -0.9438559 -0.3302692 -0.007647871 0.3420168 -0.9396869 0.003613352 0.3302792 -0.9438816 -0.001806557 -0.7273576 -0.6862261 0.006673038 -0.8467073 -0.5320207 -0.006395816 0.5495025 -0.8354758 0.005212306 0.5320284 -0.8467195 -0.003475368 -0.549502 -0.8354762 0.005212366 -0.707098 -0.707098 -0.005004763 0.7273575 -0.6862264 0.006673038 -0.3420166 -0.939687 0.003613293 0.707098 -0.707098 -0.005004763 -0.5320284 -0.8467195 -0.003475368 -0.1160929 -0.9932367 0.001876354 0.8659974 -0.4999846 0.007994651 -0.3302792 -0.9438816 -0.001806557 0.8467073 -0.5320207 -0.006395816 -0.1119641 -0.9937123 0 0.9579486 -0.2867931 0.009177029 0.9438559 -0.3302692 -0.007647871 0.9982562 -0.05814009 0.01022094 0.9936742 -0.1119591 -0.008761465 0.9847472 0.1736357 0.0111255 0.9936652 0.1119593 -0.009734928 0.9181514 0.3960516 0.01189053 0.9438307 0.3302604 -0.0105704 0.8020601 0.5971122 0.01251709 0.8466718 0.5319963 -0.0112667 0.7070576 0.7070572 -0.01182299 0.6427335 0.7659797 0.01300466 0.5319917 0.8466612 -0.01224112 0.4487588 0.8935533 0.01335233 0.3302539 0.9438092 -0.01251959 0.2305943 0.9729555 0.0135613 0.1119551 0.9936327 -0.01265794 0 0.9999072 0.0136308 -0.1119551 0.9936327 -0.01265794 -0.2305943 0.9729555 0.0135613 -0.3302539 0.9438092 -0.01251959 -0.4487591 0.8935531 0.01335221 -0.5319917 0.8466612 -0.01224112 -0.6427339 0.7659792 0.01300466 -0.7070576 0.7070572 -0.01182299 -0.8020601 0.5971122 0.01251709 -0.9181514 0.3960516 0.01189053 -0.8466718 0.5319963 -0.0112667 -0.9847472 0.1736357 0.0111255 -0.9997535 0.02171963 0.004615306 -0.9997535 -0.02171933 -0.004615306 -0.8953354 -0.4453688 0.004615426 0.3341689 -0.9424138 0.01369035 0.1420659 -0.9897626 -0.01369047 -0.8993097 -0.4372636 0.006533265 -0.5857591 -0.8103697 0.01369023 -0.7111378 -0.7029931 -0.009151577 0.7111403 -0.7029907 0.009151577 0.585758 -0.8103704 -0.01369023 0.9012817 -0.4331811 -0.006749331 -0.1420663 -0.9897626 0.01369047 -0.3341682 -0.9424141 -0.01369059 0.8926734 -0.450698 -0.002395987 0.9998581 0.01617246 0.004729747 0.999873 -0.01576292 -0.002395629 0.8779992 0.4786009 0.007655739 0.9095109 0.4156618 -0.003933429 0.5809247 0.8138515 0.01312267 0.7111431 0.7029932 -0.008725166 0.3341702 0.9424134 -0.01368933 0.1420662 0.9897626 0.0136913 -0.1420658 0.9897626 -0.01369088 -0.3341709 0.9424132 0.01368933 -0.5857574 0.8103709 -0.01369106 -0.7111409 0.70299 0.009151875 -0.8993104 0.4372619 -0.006533384 -0.8953342 0.4453711 -0.004615306 -2.37697e-6 0 -1 2.98754e-6 0 -1 0 0 -1 5.86461e-6 0 -1 9.70513e-6 0 -1 5.29964e-6 0 -1 -1.17285e-6 0 -1 4.28124e-6 0 -1 1.3484e-6 0 -1 1.67036e-6 0 -1 -1.26788e-5 0 -1 1.06693e-5 0 -1 2.26713e-6 0 -1 -5.37587e-6 0 -1 2.63218e-6 0 -1 1.71327e-5 0 -1 -6.04721e-6 0 -1 1.12833e-5 0 -1 1.71974e-5 0 -1 -1.67846e-6 0 -1 3.09191e-6 0 -1 -5.01361e-6 0 -1 1.45586e-6 0 -1 -4.00727e-6 0 -1 -1.74077e-6 0 -1 -4.07121e-6 0 -1 -8.6358e-6 0 -1 1.18103e-6 0 -1 -2.37281e-6 0 -1 -3.81593e-6 0 -1 -1.43479e-6 0 -1 5.45224e-6 0 -1 -2.81398e-6 0 -1 -1.27985e-5 0 -1 2.17516e-6 0 -1 -2.62731e-6 0 -1 4.39388e-7 0 -1 6.85609e-6 0 -1 -2.22065e-6 0 -1 1.67272e-6 0 -1 3.63916e-6 0 -1 -1.12315e-6 0 -1 -3.54372e-6 0 -1 1.7983e-6 0 -1 9.29223e-7 0 -1 8.24611e-6 0 -1 -1.67036e-6 0 -1 -9.52614e-6 0 -1 -2.3464e-6 0 -1 -2.81477e-6 0 -1 1.25885e-6 0 -1 -1.18103e-6 0 -1 2.3687e-6 0 -1 -3.91125e-6 0 -1 2.82026e-6 0 -1 -1.18265e-5 0 -1 8.35597e-6 0 -1 -4.9758e-6 0 -1 -3.34544e-6 0 -1 -9.6715e-6 0 -1 7.50592e-6 0 -1 -1.79275e-6 0 -1 6.58793e-6 0 -1 2.15903e-6 0 -1 3.72672e-6 0 -1 1.33294e-5 0 -1 -4.29137e-6 0 -1 2.11506e-6 0 -1 -3.93656e-6 0 -1 4.43238e-6 0 -1 6.887e-6 0 -1 2.05118e-6 0 -1 4.44408e-6 0 -1 -3.85561e-6 0 -1 9.11215e-6 0 -1 -1.47389e-6 0 -1 6.41313e-6 0 -1 -7.36869e-6 0 -1 -1.05002e-5 0 -1 -4.92587e-6 0 -1 -1.53541e-5 0 -1 3.46973e-6 0 -1 4.80176e-6 0 -1 -1.29459e-6 0 -1 -0.3602167 0.8212206 -0.4425389 -0.4064613 0.7275934 -0.5526275 -0.4901883 0.7502982 -0.4435858 -0.5239983 0.648956 -0.5516176 0.07157945 -0.8638045 -0.4987164 -0.6065238 0.658869 -0.444995 0.07321643 -0.8602326 -0.5046178 -0.626776 0.5516372 -0.5503166 -0.7060171 0.5495138 -0.4467376 0.2167133 -0.8323041 -0.5102013 0.2135823 -0.8434215 -0.4929733 -0.7118918 0.4383277 -0.5487067 -0.7859114 0.4253185 -0.4488291 0.3529753 -0.7808737 -0.5154073 0.3507318 -0.7995898 -0.4874868 -0.776881 0.3121779 -0.5468097 -0.84404 0.2897598 -0.4512602 0.4782176 -0.7075632 -0.5202521 0.4791375 -0.7333793 -0.4822676 -0.819869 0.1766929 -0.5446051 -0.8788321 0.1466533 -0.454034 -0.839563 0.03566318 -0.5420906 0.5890229 -0.6145778 -0.5247343 0.5951372 -0.6465007 -0.477335 -0.889402 0 -0.4571259 -0.8353077 -0.106965 -0.539277 0.6954176 -0.5412631 -0.4726826 0.6823549 -0.5046659 -0.5288707 -0.8755251 -0.1461015 -0.4605542 -0.8071315 -0.2471796 -0.5361352 -0.8376994 -0.287583 -0.4642798 0.7770648 -0.4205242 -0.4683268 0.7557017 -0.3810202 -0.5326712 -0.7557044 -0.3810185 -0.5326687 -0.7770647 -0.4205241 -0.468327 0.8376976 -0.2875846 -0.4642824 0.8071336 -0.2471785 -0.5361326 -0.6823551 -0.504666 -0.5288704 -0.6954174 -0.5412629 -0.472683 0.8755266 -0.1461007 -0.4605517 -0.5890228 -0.6145777 -0.5247347 0.8353077 -0.106965 -0.539277 -0.5951374 -0.6465007 -0.4773347 0.889402 0 -0.4571259 -0.4782219 -0.7075608 -0.5202515 0.8395648 0.035663 -0.5420879 0.8788336 0.1466525 -0.4540316 -0.4791398 -0.733378 -0.4822674 0.819869 0.1766929 -0.5446051 -0.3529778 -0.7808727 -0.5154072 0.84404 0.2897598 -0.4512602 -0.3507319 -0.7995901 -0.4874864 -0.2167133 -0.8323042 -0.5102009 0.7768834 0.3121765 -0.5468072 0.7859137 0.4253164 -0.4488269 -0.2135822 -0.8434211 -0.4929742 -0.07321643 -0.8602322 -0.5046187 0.7118931 0.4383267 -0.5487058 -0.07157868 -0.8638047 -0.4987165 0.7060187 0.5495125 -0.4467366 0.6267796 0.5516352 -0.5503145 0.6065238 0.658869 -0.444995 0.5239992 0.6489552 -0.5516178 0.4901894 0.7502976 -0.4435854 0.4064625 0.727593 -0.5526271 0.3602181 0.8212201 -0.4425386 0.2774921 0.7853653 -0.553353 0.2202226 0.8696466 -0.4418334 0.1407225 0.8206818 -0.5537858 0.07409894 0.8942091 -0.4414741 0 0.8325639 -0.553929 -0.07409894 0.8942091 -0.4414741 -0.1407211 0.820682 -0.5537859 -0.2202234 0.8696464 -0.4418333 -0.2774901 0.7853658 -0.5533533 0.2454851 0.9694004 0 0.2454851 0.9694005 0 -0.0825802 -0.9965844 0 0.4016962 0.9157731 0 0.4016972 0.9157727 0 -0.2454851 -0.9694005 0 -0.08257985 -0.9965845 0 0.5469464 0.8371676 0 0.546948 0.8371666 0 -0.401696 -0.9157731 0 -0.2454851 -0.9694004 0 0.6772804 0.7357251 0 0.6772819 0.7357237 0 -0.5469461 -0.8371679 0 -0.4016973 -0.9157726 0 0.7891407 0.6142127 0 0.7891419 0.614211 0 -0.6772804 -0.7357251 0 -0.5469483 -0.8371664 0 0.8794732 0.4759486 0 -0.6772819 -0.7357237 0 0.8794735 0.4759481 0 -0.7891409 -0.6142123 0 0.945817 0.3247004 0 -0.7891415 -0.6142114 0 -0.8794735 -0.4759481 0 -0.8794732 -0.4759486 0 0.9863615 0.1645937 0 -0.945817 -0.3247004 0 0.9863618 0.1645924 0 1 0 0 -0.9863618 -0.1645924 0 -0.9863615 -0.1645937 0 0.9863615 -0.1645937 0 -1 0 0 0.9863618 -0.1645924 0 -0.9863615 0.1645937 0 0.945817 -0.3247004 0 -0.9863618 0.1645924 0 -0.945817 0.3247004 0 0.7891407 -0.6142127 0 0.8794735 -0.4759481 0 0.8794732 -0.4759486 0 -0.8794732 0.4759486 0 0.7891419 -0.614211 0 -0.8794735 0.4759481 0 0.6772804 -0.7357251 0 0.6772819 -0.7357237 0 -0.7891415 0.6142114 0 -0.7891409 0.6142123 0 0.5469461 -0.8371679 0 0.5469483 -0.8371664 0 -0.6772819 0.7357237 0 -0.6772804 0.7357251 0 0.2454851 -0.9694004 0 0.401696 -0.9157731 0 0.4016973 -0.9157726 0 -0.5469483 0.8371664 0 0.0825802 -0.9965844 0 -0.5469461 0.8371679 0 0.2454851 -0.9694005 0 0.08257985 -0.9965845 0 -0.4016973 0.9157726 0 -0.401696 0.9157731 0 -0.2454851 0.9694004 0 -0.2454851 0.9694005 0 -0.08257985 0.9965845 0 -0.0825802 0.9965844 0 0.0825802 0.9965844 0 0.08257985 0.9965845 0 -2.06372e-5 3.35596e-7 1 0 0 1 0 -1.77715e-6 1 -8.23067e-6 6.61956e-6 1 4.83364e-6 2.42932e-6 1 7.22358e-6 2.80879e-6 1 -1.47052e-5 2.56389e-6 1 1.96179e-5 -4.48496e-7 1 -2.28028e-6 4.31188e-7 1 1.9715e-5 -4.28269e-6 1 0 -5.73077e-6 1 3.04055e-6 6.44504e-6 1 0 1.64508e-6 1 3.71933e-6 7.25327e-6 1 -1.50228e-5 1.30962e-6 1 2.0667e-6 -4.70307e-7 1 0 1.72505e-6 1 0 3.04048e-6 1 7.89023e-6 0 1 0 -8.19903e-6 1 1.60717e-6 0 1 8.66849e-6 1.54314e-6 1 0 1.64174e-6 1 0 1.27384e-6 1 4.58667e-6 7.3777e-6 1 0 -9.51329e-7 1 -4.55144e-6 3.9053e-7 1 0 1.25894e-6 1 1.16154e-6 3.98657e-7 1 -1.60143e-5 1.20044e-6 1 0 -1.73427e-6 1 0 -1.17358e-6 1 0 1.30866e-6 1 3.09372e-6 -1.85526e-6 1 4.13661e-7 0 1 1.13356e-6 0 1 1.16937e-5 -3.28479e-6 1 6.04334e-6 3.18304e-6 1 0 1.73427e-6 1 -9.29093e-6 3.91477e-6 1 0 1.15499e-6 1 0 3.94334e-6 1 0 1.30352e-6 1 4.1171e-6 0 1 1.04962e-6 1.19761e-6 1 0 3.65542e-6 1 4.2501e-6 7.60809e-7 1 8.83275e-6 8.41849e-7 1 0 1.29793e-6 1 -2.2456e-6 0 1 0 3.53629e-6 1 0 1.85526e-6 1 0 -3.94334e-6 1 0 -3.65542e-6 1 0 -3.53629e-6 1 -1.33608e-5 1.22972e-6 1 0 1.31963e-6 1 0 0 1 0 1.17358e-6 1 0 4.90609e-7 1 4.4871e-6 0 1 1.09224e-5 -5.42387e-6 1 0 1.00579e-6 1 -1.06791e-5 3.25311e-6 1 0 0 1 -2.09982e-6 -1.27404e-6 1 -1.55916e-5 3.28479e-6 1 0 -3.91477e-6 1 -3.02167e-6 -3.18305e-6 1 0 -1.31392e-6 1 1.33608e-5 -1.22972e-6 1 -8.83275e-6 -8.41849e-7 1 -6.13385e-7 9.45961e-7 1 1.69252e-6 1.73427e-6 1 -7.89023e-6 0 1 0 -1.00579e-6 1 0 -1.73427e-6 1 -8.2342e-6 0 1 -1.13356e-6 0 1 0 -9.45961e-7 1 -4.14595e-6 -4.90609e-7 1 -2.09923e-6 -1.19761e-6 1 0 -1.30866e-6 1 1.60143e-5 -1.20044e-6 1 -8.66849e-6 -1.54314e-6 1 0 -3.98657e-7 1 0 -1.64174e-6 1 -4.58667e-6 -7.37771e-6 1 0 -1.25894e-6 1 -8.50169e-7 0 1 0 -1.27384e-6 1 0 -1.64508e-6 1 1.50228e-5 -1.30962e-6 1 -2.24205e-5 4.48496e-7 1 1.36693e-6 0 1 0 8.73702e-6 1 1.47052e-5 -2.56389e-6 1 -3.89885e-6 -1.72505e-6 1 0 -3.04048e-6 1 0 -1.95716e-6 1 -5.41769e-6 -2.80879e-6 1 -6.23457e-6 5.68836e-6 1 1.22196e-5 -5.5745e-6 1 3.42386e-6 -8.61243e-7 1 3.20859e-6 8.06297e-7 1 0 1.28862e-6 1 0 1.20646e-6 1 4.55144e-6 -3.9053e-7 1 0 9.51329e-7 1 0 1.28197e-6 1 6.09897e-6 -6.48848e-6 1 8.50926e-6 5.03471e-7 1 0 9.85972e-7 1 0 1.77715e-6 1 -3.44564e-6 -6.71954e-6 1 1.12696e-6 -4.26203e-7 1 0 2.95713e-6 1 0 7.3083e-6 1 -3.51935e-6 0 1 -1.90799e-5 -2.64015e-6 1 -4.22704e-6 0 1 4.19965e-6 -1.27404e-6 1 3.01458e-6 -1.95716e-6 1 1.096e-5 5.12231e-6 1 0 2.55631e-6 1 -6.10978e-6 -5.57451e-6 1 -5.46119e-6 -5.42387e-6 1 1.39648e-5 6.37066e-6 1 3.06479e-6 6.0877e-6 1 -7.29192e-6 2.83536e-6 1 -1.39648e-5 -6.37066e-6 1 0 5.90794e-6 1 4.52316e-6 -1.14593e-6 1 0 5.7465e-6 1 0 -6.08771e-6 1 -2.26158e-6 1.14593e-6 1 -6.84997e-6 -5.12231e-6 1 0 -2.95713e-6 1 0 -2.55631e-6 1 7.29192e-6 -2.83536e-6 1 0 0 1 -2.11739e-6 1.2847e-6 1 1.90799e-5 2.64015e-6 1 0 1.97492e-6 1 -9.27135e-7 -8.19903e-6 1 0 0 1 0 -5.03471e-7 1 0 -9.85972e-7 1 0.999506 0.03074401 -0.006533503 0.999506 -0.03074258 0.006533443 -0.0989505 0.9950817 0.004615545 0.9094814 0.4156439 0.009151279 0.956381 0.2919791 -0.009151279 -0.1420735 0.9898454 -0.004615187 0.7277485 0.685813 -0.006533324 -0.5500469 0.8351211 0.004615128 0.7339175 0.679223 -0.004615128 -0.5857943 0.8104467 -0.004615724 0.374822 0.9270853 0.004615306 -0.8587495 0.5123805 0.003933429 0.3342059 0.9424889 -0.004615426 -0.8926498 0.450686 -0.007656037 -0.9825249 0.1859272 0.008725047 -0.9997897 0.01576167 -0.01312214 -0.9669647 -0.2545724 0.01312261 -0.7588465 -0.6512245 0.007655918 -0.9094843 -0.4156467 -0.008724331 -0.7484984 -0.6631172 0.00506258 -0.5222384 -0.8527505 -0.009151399 -0.40513 -0.9142134 0.009151399 -0.08994656 -0.9959252 -0.006533503 -0.09893697 -0.995083 -0.004615485 0.3342103 -0.9424874 0.004615128 0.3748244 -0.9270844 -0.004615545 0.7339195 -0.6792209 0.004615306 0.7277502 -0.6858112 0.006533086 0.9563818 -0.2919763 0.009151518 0.9094806 -0.4156458 -0.009151339 0.9997535 -0.02172017 0.004615247 0.9997535 0.02171701 -0.004615247 0.8953355 0.4453687 0.004615306 -0.3342071 0.9424884 0.004615366 0.8751477 0.483834 -0.004615604 -0.3748208 0.9270858 -0.004615426 0.5857948 0.8104463 0.004615843 -0.7111686 0.7030104 0.003933608 0.5500465 0.8351213 -0.004614949 -0.8854601 0.4647156 0 0.1420737 0.9898454 0.004615366 -0.7277612 0.6858307 0 0.09895068 0.9950817 -0.004615545 -0.9071653 0.4207358 -0.005719006 -0.9825252 0.1859253 0.008724927 -0.9997897 0.01576161 -0.01312237 -0.9669649 -0.2545716 0.01312255 -0.7588444 -0.6512271 0.00765556 -0.909484 -0.4156474 -0.008724749 -0.7111679 -0.7030113 -0.003933191 -0.3748263 -0.9270836 0.004615545 -0.334209 -0.9424878 -0.004615128 0.09893757 -0.995083 0.004615247 0.08994573 -0.9959252 0.006533563 0.5499991 -0.8350531 0.013691 0.4051293 -0.9142136 -0.009151399 0.8751244 -0.4838212 0.008635997 0.7277389 -0.6857995 -0.008669555 0.9095127 -0.4156576 -0.003933191 0.9997535 -0.02171695 0.004615247 0.9997535 0.02172017 -0.004615247 0.9095131 0.4156566 0.003933191 -0.3342103 0.9424874 0.004615128 0.7277392 0.6857993 0.008669555 0.8751244 0.4838209 -0.008636057 -0.3748244 0.9270844 -0.004615545 -0.7111697 0.7030094 0.003933191 0.40513 0.9142134 0.009151399 0.5499985 0.8350535 -0.013691 0.08994656 0.9959252 -0.006533503 -0.7277624 0.6858294 0 0.09893697 0.995083 -0.004615485 -0.9071661 0.4207339 -0.005719006 -0.9825252 0.1859256 0.008724868 -0.9997897 0.01576155 -0.01312243 -0.9669643 -0.2545741 0.0131222 -0.7588431 -0.6512286 0.007655382 -0.7111669 -0.7030123 -0.003933727 -0.374822 -0.9270853 0.004615306 -0.3342059 -0.9424889 -0.004615426 0.0989505 -0.9950817 0.004615545 0.1420735 -0.9898454 -0.004615187 0.5500469 -0.8351211 0.004615128 0.5857943 -0.8104467 -0.004615724 0.8751491 -0.4838316 0.004615545 0.8953344 -0.4453708 -0.004615426 0.9997535 -0.02171963 0.004615306 0.9997535 0.02171933 -0.004615306 0.8953354 0.4453688 0.004615426 -0.3341689 0.9424138 0.01369035 -0.1420659 0.9897626 -0.01369047 0.8993097 0.4372636 0.006533265 0.5857591 0.8103697 0.01369023 0.7111378 0.7029931 -0.009151577 -0.7111403 0.7029907 0.009151577 -0.585758 0.8103704 -0.01369023 -0.8854476 0.464712 -0.005062043 0.1420663 0.9897626 0.01369047 0.3341682 0.9424141 -0.01369059 -0.8926498 0.450686 -0.007656157 -0.9709267 0.2393131 0.005547821 -0.9984998 -0.05461466 0.00393325 -0.9998465 0.01576292 -0.007655918 -0.8779992 -0.4786009 0.007655739 -0.9095109 -0.4156618 -0.003933429 -0.5809247 -0.8138515 0.01312267 -0.7111431 -0.7029932 -0.008725166 -0.3341702 -0.9424134 -0.01368933 -0.1420662 -0.9897626 0.0136913 0.3341709 -0.9424132 0.01368933 0.1420658 -0.9897626 -0.01369088 0.7111409 -0.70299 0.009151875 0.5857574 -0.8103709 -0.01369106 0.8993104 -0.4372619 -0.006533384 0.8953342 -0.4453711 -0.004615306 0.9995061 0.03074365 -0.006533443 0.9995061 -0.03074294 0.006533503 -0.09893757 0.995083 0.004615247 0.9094811 0.4156447 0.009151458 0.9563818 0.2919762 -0.009151577 -0.08994573 0.9959252 0.006533563 0.7277501 0.6858114 -0.006533145 -0.5499991 0.8350531 0.013691 -0.4051293 0.9142136 -0.009151399 0.7339192 0.6792212 -0.004615306 0.3748263 0.9270836 0.004615545 -0.8587377 0.512376 0.006370961 -0.7277389 0.6857995 -0.008669555 0.334209 0.9424878 -0.004615128 -0.9071652 0.4207359 -0.005719125 -0.9825259 0.1859217 0.008724987 -0.9997897 0.01576334 -0.01312214 -0.9669637 -0.2545765 0.01312237 -0.7801063 -0.6256209 0.005718588 -0.9094848 -0.415646 -0.00872457 -0.5424842 -0.840066 0 -0.748509 -0.6631247 0 -0.5222584 -0.8527783 -0.003933191 -0.1420737 -0.9898454 0.004615366 -0.09895068 -0.9950817 -0.004615545 0.3342071 -0.9424884 0.004615366 0.3748208 -0.9270858 -0.004615426 0.7339178 -0.6792227 0.004615008 0.7277479 -0.6858137 0.006533324 0.9563814 -0.2919775 0.00915122 + + + + + + + + + + + + + + +

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

+
+
+
+
+ + + + + 0.6859207 -0.3240135 0.6515582 7.481132 0.7276763 0.3054208 -0.6141704 -6.50764 0 0.8953956 0.4452714 5.343665 0 0 0 1 + + + + -0.2908646 -0.7711008 0.5663932 4.076245 0.9551712 -0.1998834 0.2183912 1.005454 -0.05518906 0.6045247 0.7946723 5.903862 0 0 0 1 + + + + 1 0 0 0 0 1 0 0 0 0 1 0 0 0 0 1 + + + + + + + + + + + + + +
\ No newline at end of file diff --git a/kuka_kr5_support/package.xml b/kuka_kr5_support/package.xml new file mode 100644 index 000000000..39d0e48b7 --- /dev/null +++ b/kuka_kr5_support/package.xml @@ -0,0 +1,48 @@ + + + kuka_kr5_support + 0.1.0 + +

+ ROS-Industrial support for the KUKA KR5 (and variants). +

+

+ This package contains configuration data, 3D models and launch files + for KUKA KR 5 manipulators. This currently includes the KR 5 arc only. +

+

Specifications:

+
    +
  • KR 5 arc - Default
  • +
+

+ Joint limits and maximum joint velocities are based on the information + found in the online datasheet. All urdfs are based on the default motion and joint velocity limits, + unless noted otherwise. +

+

+ Before using any of the configuration files and / or meshes included + in this package, be sure to check they are correct for the particular + robot model and configuration you intend to use them with. +

+

+ NB: this package currently uses non-valid inertia parameters. +

+
+ Denis Štogl + Denis Štogl + G.A. vd. Hoorn (TU Delft Robotics Institute) + BSD + + http://wiki.ros.org/kuka_kr5_support + https://github.com/ros-industrial/kuka_experimental/issues + https://github.com/ros-industrial/kuka_experimental + + ament_cmake + + rviz2 + xacro + + + ament_cmake + +
diff --git a/kuka_kr5_support/test/roslaunch_test.xml b/kuka_kr5_support/test/roslaunch_test.xml new file mode 100644 index 000000000..e5176c771 --- /dev/null +++ b/kuka_kr5_support/test/roslaunch_test.xml @@ -0,0 +1,9 @@ + + + + + + + + + diff --git a/kuka_kr5_support/urdf/kr5_arc.xacro b/kuka_kr5_support/urdf/kr5_arc.xacro new file mode 100644 index 000000000..8e02c1721 --- /dev/null +++ b/kuka_kr5_support/urdf/kr5_arc.xacro @@ -0,0 +1,5 @@ + + + + + diff --git a/kuka_kr5_support/urdf/kr5_arc_macro.ros2_control.xacro b/kuka_kr5_support/urdf/kr5_arc_macro.ros2_control.xacro new file mode 100644 index 000000000..16a9db9ad --- /dev/null +++ b/kuka_kr5_support/urdf/kr5_arc_macro.ros2_control.xacro @@ -0,0 +1,57 @@ + + + + + + + + ros2_control_kuka_demo_driver/KukaSystemPositionOnlyHardware + ${rsi_ip} + 49152 + + + + -1 + 1 + + + + + + -1 + 1 + + + + + + -1 + 1 + + + + + + -1 + 1 + + + + + + -1 + 1 + + + + + + -1 + 1 + + + + + + + diff --git a/kuka_kr5_support/urdf/kr5_arc_macro.xacro b/kuka_kr5_support/urdf/kr5_arc_macro.xacro new file mode 100644 index 000000000..3d8f3f0af --- /dev/null +++ b/kuka_kr5_support/urdf/kr5_arc_macro.xacro @@ -0,0 +1,278 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/kuka_kr5_support/urdf/kr5_arc_ros2.xacro b/kuka_kr5_support/urdf/kr5_arc_ros2.xacro new file mode 100644 index 000000000..83f93bbe2 --- /dev/null +++ b/kuka_kr5_support/urdf/kr5_arc_ros2.xacro @@ -0,0 +1,10 @@ + + + + + + + + + + diff --git a/kuka_rsi_simulator/kuka_rsi_simulator/__pycache__/__init__.cpython-38.pyc b/kuka_rsi_simulator/kuka_rsi_simulator/__pycache__/__init__.cpython-38.pyc deleted file mode 100644 index 1c6230de8..000000000 Binary files a/kuka_rsi_simulator/kuka_rsi_simulator/__pycache__/__init__.cpython-38.pyc and /dev/null differ diff --git a/kuka_rsi_simulator/kuka_rsi_simulator/__pycache__/kuka_rsi_simulator.cpython-38.pyc b/kuka_rsi_simulator/kuka_rsi_simulator/__pycache__/kuka_rsi_simulator.cpython-38.pyc deleted file mode 100644 index 21765e2b0..000000000 Binary files a/kuka_rsi_simulator/kuka_rsi_simulator/__pycache__/kuka_rsi_simulator.cpython-38.pyc and /dev/null differ