From 9f9ba64551ec12caa08ccf8a0a0ee6849799598b Mon Sep 17 00:00:00 2001 From: Manuel M Date: Wed, 11 Jan 2023 07:42:45 +0100 Subject: [PATCH] add kuka_kr16_support --- kuka_kr16_support/CMakeLists.txt | 16 + .../config/joint_names_kr16.yaml | 1 + .../config/rviz/view_robot_kr16_2.rviz | 249 +++++++++++ kuka_kr16_support/launch/load_kr16_2.launch | 5 + kuka_kr16_support/launch/test_kr16_2.launch | 9 + .../launch/view_kr16_2.launch.py | 71 ++++ .../meshes/kr16_2/collision/base_link.stl | Bin 0 -> 20384 bytes .../meshes/kr16_2/collision/link_1.stl | Bin 0 -> 30284 bytes .../meshes/kr16_2/collision/link_2.stl | Bin 0 -> 32184 bytes .../meshes/kr16_2/collision/link_3.stl | Bin 0 -> 22084 bytes .../meshes/kr16_2/collision/link_4.stl | Bin 0 -> 31484 bytes .../meshes/kr16_2/collision/link_5.stl | Bin 0 -> 15284 bytes .../meshes/kr16_2/collision/link_6.stl | Bin 0 -> 15484 bytes .../meshes/kr16_2/visual/base_link.dae | 100 +++++ .../meshes/kr16_2/visual/link_1.dae | 311 ++++++++++++++ .../meshes/kr16_2/visual/link_2.dae | 100 +++++ .../meshes/kr16_2/visual/link_3.dae | 395 ++++++++++++++++++ .../meshes/kr16_2/visual/link_4.dae | 198 +++++++++ .../meshes/kr16_2/visual/link_5.dae | 100 +++++ .../meshes/kr16_2/visual/link_6.dae | 100 +++++ kuka_kr16_support/package.xml | 47 +++ kuka_kr16_support/test/roslaunch_test.xml | 9 + kuka_kr16_support/urdf/kr16_2.urdf | 217 ++++++++++ kuka_kr16_support/urdf/kr16_2.xacro | 6 + kuka_kr16_support/urdf/kr16_2_macro.xacro | 225 ++++++++++ 25 files changed, 2159 insertions(+) create mode 100644 kuka_kr16_support/CMakeLists.txt create mode 100644 kuka_kr16_support/config/joint_names_kr16.yaml create mode 100644 kuka_kr16_support/config/rviz/view_robot_kr16_2.rviz create mode 100644 kuka_kr16_support/launch/load_kr16_2.launch create mode 100644 kuka_kr16_support/launch/test_kr16_2.launch create mode 100644 kuka_kr16_support/launch/view_kr16_2.launch.py create mode 100644 kuka_kr16_support/meshes/kr16_2/collision/base_link.stl create mode 100644 kuka_kr16_support/meshes/kr16_2/collision/link_1.stl create mode 100644 kuka_kr16_support/meshes/kr16_2/collision/link_2.stl create mode 100644 kuka_kr16_support/meshes/kr16_2/collision/link_3.stl create mode 100644 kuka_kr16_support/meshes/kr16_2/collision/link_4.stl create mode 100644 kuka_kr16_support/meshes/kr16_2/collision/link_5.stl create mode 100644 kuka_kr16_support/meshes/kr16_2/collision/link_6.stl create mode 100644 kuka_kr16_support/meshes/kr16_2/visual/base_link.dae create mode 100644 kuka_kr16_support/meshes/kr16_2/visual/link_1.dae create mode 100644 kuka_kr16_support/meshes/kr16_2/visual/link_2.dae create mode 100644 kuka_kr16_support/meshes/kr16_2/visual/link_3.dae create mode 100644 kuka_kr16_support/meshes/kr16_2/visual/link_4.dae create mode 100644 kuka_kr16_support/meshes/kr16_2/visual/link_5.dae create mode 100644 kuka_kr16_support/meshes/kr16_2/visual/link_6.dae create mode 100644 kuka_kr16_support/package.xml create mode 100644 kuka_kr16_support/test/roslaunch_test.xml create mode 100644 kuka_kr16_support/urdf/kr16_2.urdf create mode 100644 kuka_kr16_support/urdf/kr16_2.xacro create mode 100644 kuka_kr16_support/urdf/kr16_2_macro.xacro diff --git a/kuka_kr16_support/CMakeLists.txt b/kuka_kr16_support/CMakeLists.txt new file mode 100644 index 000000000..770599dc6 --- /dev/null +++ b/kuka_kr16_support/CMakeLists.txt @@ -0,0 +1,16 @@ +cmake_minimum_required(VERSION 3.5) + +project(kuka_kr16_support) + +find_package(ament_cmake REQUIRED) + +if (CATKIN_ENABLE_TESTING) + find_package(roslaunch REQUIRED) + roslaunch_add_file_check(test/roslaunch_test.xml) +endif() + +install(DIRECTORY config launch meshes urdf + DESTINATION share/${PROJECT_NAME} +) + +ament_package() \ No newline at end of file diff --git a/kuka_kr16_support/config/joint_names_kr16.yaml b/kuka_kr16_support/config/joint_names_kr16.yaml new file mode 100644 index 000000000..1a23ced85 --- /dev/null +++ b/kuka_kr16_support/config/joint_names_kr16.yaml @@ -0,0 +1 @@ +controller_joint_names: ['joint_a1', 'joint_a2', 'joint_a3', 'joint_a4', 'joint_a5', 'joint_a6'] diff --git a/kuka_kr16_support/config/rviz/view_robot_kr16_2.rviz b/kuka_kr16_support/config/rviz/view_robot_kr16_2.rviz new file mode 100644 index 000000000..77b895b52 --- /dev/null +++ b/kuka_kr16_support/config/rviz/view_robot_kr16_2.rviz @@ -0,0 +1,249 @@ +Panels: + - Class: rviz_common/Displays + Help Height: 78 + Name: Displays + Property Tree Widget: + Expanded: ~ + Splitter Ratio: 0.5 + Tree Height: 745 + - 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 + - Class: rviz_common/Time + Experimental: false + Name: Time + SyncMode: 0 + SyncSource: "" +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 + - Class: rviz_default_plugins/TF + Enabled: true + Frame Timeout: 15 + Frames: + All Enabled: true + base: + Value: true + base_link: + Value: true + flange: + Value: true + link_1: + Value: true + link_2: + Value: true + link_3: + Value: true + link_4: + Value: true + link_5: + Value: true + link_6: + Value: true + tool0: + Value: true + Marker Scale: 1 + Name: TF + Show Arrows: true + Show Axes: true + Show Names: false + Tree: + base_link: + base: + {} + link_1: + link_2: + link_3: + link_4: + link_5: + link_6: + flange: + tool0: + {} + Update Interval: 0 + 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 + flange: + Alpha: 1 + Show Axes: false + Show Trail: false + 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 + Mass Properties: + Inertia: false + Mass: 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 + Covariance x: 0.25 + Covariance y: 0.25 + Covariance yaw: 0.06853891909122467 + 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: 4.382266521453857 + Enable Stereo Rendering: + Stereo Eye Separation: 0.05999999865889549 + Stereo Focal Distance: 1 + Swap Stereo Eyes: false + Value: false + Focal Point: + X: 0.4607224464416504 + Y: 0.24497589468955994 + Z: 0.1281789243221283 + Focal Shape Fixed Size: true + Focal Shape Size: 0.05000000074505806 + Invert Z Axis: false + Name: Current View + Near Clip Distance: 0.009999999776482582 + Pitch: 0.155398428440094 + Target Frame: + Value: Orbit (rviz) + Yaw: 5.303589820861816 + Saved: ~ +Window Geometry: + Displays: + collapsed: false + Height: 1036 + Hide Left Dock: false + Hide Right Dock: false + QMainWindow State: 000000ff00000000fd00000004000000000000015600000372fc0200000008fb0000001200530065006c0065006300740069006f006e00000001e10000009b0000005c00fffffffb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000001ed000001df00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c006100790073010000003b00000372000000c700fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261000000010000010f00000372fc0200000003fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a00560069006500770073010000003b00000372000000a000fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e100000197000000030000077c0000003efc0100000002fb0000000800540069006d006501000000000000077c0000025300fffffffb0000000800540069006d006501000000000000045000000000000000000000050b0000037200000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000 + Selection: + collapsed: false + Time: + collapsed: false + Tool Properties: + collapsed: false + Views: + collapsed: false + Width: 1916 + X: 0 + Y: 20 diff --git a/kuka_kr16_support/launch/load_kr16_2.launch b/kuka_kr16_support/launch/load_kr16_2.launch new file mode 100644 index 000000000..7a7b82d04 --- /dev/null +++ b/kuka_kr16_support/launch/load_kr16_2.launch @@ -0,0 +1,5 @@ + + + + + diff --git a/kuka_kr16_support/launch/test_kr16_2.launch b/kuka_kr16_support/launch/test_kr16_2.launch new file mode 100644 index 000000000..44260a938 --- /dev/null +++ b/kuka_kr16_support/launch/test_kr16_2.launch @@ -0,0 +1,9 @@ + + + + + + + + + diff --git a/kuka_kr16_support/launch/view_kr16_2.launch.py b/kuka_kr16_support/launch/view_kr16_2.launch.py new file mode 100644 index 000000000..7ef0cb4eb --- /dev/null +++ b/kuka_kr16_support/launch/view_kr16_2.launch.py @@ -0,0 +1,71 @@ +# Copyright 2021 Stogl Robotics Consulting UG (haftungsbeschränkt) +# +# 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. + +from launch import LaunchDescription +from launch.actions import RegisterEventHandler +from launch.event_handlers import OnProcessExit +from launch.substitutions import Command, FindExecutable, PathJoinSubstitution + +from launch_ros.actions import Node +from launch_ros.substitutions import FindPackageShare + + +def generate_launch_description(): + + # Get URDF via xacro + robot_description_content = Command( + [ + PathJoinSubstitution([FindExecutable(name="xacro")]), + " ", + PathJoinSubstitution( + [FindPackageShare("kuka_kr16_support"), "urdf", + "kr16_2.xacro"] + ), + ] + ) + + robot_description = {"robot_description": robot_description_content} + + joint_state_publisher_node = Node( + package="joint_state_publisher_gui", + executable="joint_state_publisher_gui", + ) + + robot_state_publisher_node = Node( + package="robot_state_publisher", + executable="robot_state_publisher", + output="both", + parameters=[robot_description], + ) + + rviz_config_file = PathJoinSubstitution( + [FindPackageShare("kuka_kr16_support"), "config/rviz", + "view_robot_kr16_2.rviz"] + ) + + rviz_node = Node( + package="rviz2", + executable="rviz2", + name="rviz2", + output="log", + arguments=["-d", rviz_config_file] + ) + + nodes = [ + joint_state_publisher_node, + robot_state_publisher_node, + rviz_node + ] + + return LaunchDescription(nodes) diff --git a/kuka_kr16_support/meshes/kr16_2/collision/base_link.stl b/kuka_kr16_support/meshes/kr16_2/collision/base_link.stl new file mode 100644 index 0000000000000000000000000000000000000000..561cff97065963ef92fbfaf91594608827b95300 GIT binary patch literal 20384 zcmb_kdAyEA`=27q!692oA%twnTAX_(+p!*75k*9H%Dx;9w=B^{lqKnXODbt4TAXL5 zLPUiSWhq2&CrNcm^@?|{xn~~VInU$s`{#E)pYt@H`})px%{A9t+uWxfE!$N3|NL2e z8Ds43E0z8X+idKnhG#!1M+YhVfs*+GJC-zl`lHX}@0}X)M~)l`7<>P*sv@g=E785o z_3OLWN#(!wZN^_*zPVYY9ry8X2b>5Vtkxpf`Sb#=Ck^QPI6{5evH5yS6(cH(mPBO{ zu?X>w<}tl|E0T;MRWdZq#F)~E$yzExB$K4XnaydwR7#(XKAyd`ca}Q*MR8s=^K;UPB#m0xCCN@Y>~&$V zjC8oW>^186->uXGAKzuP>z@2HVT}x@cb2oVr*ImtZq-GO{$rBX`rB9JQ;V11t#StN z0H4r!?uagOdD#ixOpJAYvaH(jN)ff~i>sC6zHh@XPCv$Wr?wXIrsaK&jWPD_qeo@V z9W7P+n|_suKq|MsXywz2{vq!V`x#42CJFI#Ges-ke*Vee{f{d0m+MSbsKuG@J{8;l z$z)?+ZqFkgvzo4wuVgQkHFF25|GZaO_BuCQ(%zs{gBA~vr@G!^*Kum~K3U+h6S3;w z4pR68PwgEmM#!Phm9>a>>X%iU_NS=Azm{|7+~^0<$d9pKM^zP#|7t0Q^}foTRAbfO z%r4H4pRHlehi_MGXEkvur@45z?+u>CA;O(OvL42M(Chewod~Mwbv*Rm0QvRjO*rYq z%5KK!l^FZ}&wO&=m|{Vp4Ot#y@ptv*i|++SyNG6N+w6sMB|m$+LEi|=bv_yv6nV1l!f0PBgStjDv=7&H&x#%*F4siuUPz*MtpGB zLV0}s7;*i&RB7$U$c_lI67n$-k0gbi_xZQojfzi|0XbZ!3=gq$ z{MEemZ^tT5KC(<+(0aS5+b-amtg z_7SJ`8Js_+Sd7k~J$Ga=41J03ecC=;Sk^4mCD`86Keae-Fr$XN_U+zQssl#^AAf$b z_@n1nL6eEagV{QckVcO^$Ad02dz!KHqEY1R)v7SBa%hU!oAH~6K&qENRB6)&_BLq7 z_HI3%t$JsP>^;T3NbgQC?TtINk#DcEf2%BhWgT(qLPdod?UV11*tGF8jO@53##X`QQnTRZE{SJ zHoW1%uRV{-7{6k#EdOgs(eyw=&k_-VGch*d&7<(y&9q!t5fdZu{j@) zR}Vfq&&v(63*VOg>pgwU`Otfwt@qrF8EbbZljElhSGzh(j!(3W#k7qXDnFj*Zs;n< z?(U{mJy1|+>x*gYGgO0uk+JD3x+g)5n^Q}+o7z{6oSVaOUPSvm)~nmXQR}b^8?cZlzn~nL!U{JAY0QfGlSI2REBs)c5Vtp|kIlWU9M%iiH%$q(%ZF@CMZXJ0x8|OtTL^F15XE`+? zXQG^4u%&Q3$Y+pdNyFs3Ty}O_qh~dblD|whS!KrI*F9ai6P#CX`g~~ZrgnTIcwm4>q46uUNJ)xUG@o z4ng1R_;Fh!RjK~j*z`*EJp}2e{K8gp<`oa-S^1s^YN=C;bPTzznLwS;$)Yntx}vj4 zXNSg&)fjM-nq2>2?3(en2z-JP;!KQvx%N8V_NP>NU`VFRGECIp(|ZH+*|aZqzDj6#VV2?0k?pdAx2pxSiir1)UMsPJXguswIp|Tr+wVA>C!Xi;IYj-~ zekcFxrQ=?ffe6eWbZhC0zvTTr`|+PM{E7t;$eXbz4&_t*`&Q=Pue?*?T!`@Vl5Od? zsQ$ZZiS&t$ahMwIrK9uKx1jPs({KM}CNA z?Bu!0s{L;rrRusehVmj6jU8{sa`xSzHlD32Ypmd2RHGb`GBnyjjBr}J1Fly!Uwb`m z?y7Y0PQw}U%#5W8@fG7PWB07TQjI>9k2gQw*~D6x0U)~8(NOkDf7Z;z*muWjsNY79 zjBVK^yy#3BG3CD`mCs|&&^oF@fmm$U-lkrxMFhs(DAu<7DV0;KweeM30%KU8yC@NP zpH4sD!1I4tP(E^drdssYJU+W~s)@)u4nNK-kAEkd&@O&Nh#~7L@vVbXACfZ=6l9QKYv*Mct)rjDlmn;Fht-?jP=lnO&T#=BQSa) z0%u}uPU}iy&VV)|b;LEnjWrAKrCIe%1i-lKX8==p88L24XK}@2*90T>{2A6Uk3hi1rar-4EMSebF=|c?#{r)|7 zabSBr27zcF(cs>};&6$rvdMoNQ_aC$%|TfuMF&_%EYekF)?eh*`c_V^Uza15)ov2R zPQCK$Q%kE=dgYe8nai%+Agtab@ndYc)^4#L71fVgyZFSe+)&|6y346ot$)=YwDRZ{ z$?&i%j}XxPV$5n+-K@2X^LhxFN#DeD7$x>CSj4}~Y0fFLqYRJarHqgAIM9{NcTZIv zAx_VDjh}feaN0Fgi1zoxYL}CC(O#{llkl)R$Y}?W%I;N?s}YsQS(+CV{VU=Yp^(z!!4WBsEWEK?IYD)Puk<-U(jt-W0`2*;feZcI`kI)1OF zDpuI^Ha>ClB07o&TQ=sGm6z3wDP0?22hwKx#DM2Kz*Rm4VUS@Pv+FVV$DN2)Tg9Qk)g6Zpd^U8x+im4 zzNVs)?#bA!&rsR^OcF%bl(*!9F6m;)!v(zz;KzNho4((j>lVguGoqg52bl}xyOSD- z5-(LZoe3u|B9OO^im}3~?o*BVr0=^4q;gp?)%|{!@#v@v@~gx5@RSdGh_Bj(^59!5 zP5yysA92gJn!&lXt@#hRnXY!${(`Y;tJlXirDd71-G9@+W~}s=<%9RfW$@!qXDXz^ zddElnI&_4pUg{yad&%QoW=VNlp?V!;#l|DzIdya^Q)2B1^-anwId%SggK$)sz51DD zxy>Whk24;WFKwA8kqUXx_+n0dy8pYfSy~CjdvSsNJsqoJ+LKDMF~=j?!Fo@BBnOT! zs8X7=5J;sXkJMf@2_mEOm$KN=)3U~-HbO@HpznBEkdCsS@)9CZ^#m21# z&WmVYs^&A#%YW_OAUlk0FGvbPk?gbvk}`1}50%Q5HE-T5m(Oi4NFtisPyyQK(Xq_8 zl73T5wi75jt%3fX$Ybf*A7tI{cgyyr+Y6-f_<1+g*RIX4CO*Gf&fC*YpzPFlrTt0d zF=9xH>OSKcIeKMVfmGVhORByS5ifjOR*m|6hFsI9mC(Ljx`>S3L4W0y$Cgls+sv24 z_NNP+7tuZ4y&4A*G0C>ld|`cpejM6I zG=HL)T5#*Kv<*Rbfi)T3WKh3{b`UE)#%vwMsgAO>lfG4F%vMFF3Uhf$6gh1j#i@=$ zDy-XlgzYU!>MdbiWBsm)wHT?R{OZ7hMUwI>%;9W)Wh~KVPG-!Q&95ZoSNH@oS)57t zOLV4xvVS2(nLa+TnZB79^HRoaH6f{*z#JD5I1^(R_Kg*M{utT0R4b1M#dX)G#x*h4 z;N0g~n z$3q~MpY<*3vtAC%I>#ps>EI!3Helwp*@xv(=J6c4J9{Qyva6Su_1So3ED0z829w!gkdZb=AUaGvj=l3T zRC+Jyy&N<4XR`0&D0mmgP}$q8BnaCbRMZ_rf3AHL^$?RFYzIyQ4mj_RfY1*W@Eo^!;FoBIDEt`hF1SMYNA7bmT=jVqq!q@E+m$D_iMtk_x>x zW9tXLE)NYaB>wJ@?y5UOg$UnY)i}FRj@|zQpEbI($HUfY28~{uv1{-CNT#hkz<*lN z&DBwc3K2e!+`;?g@AKC1kGl5sc%ZMfHILX$JIFIL}4_*-T-5# z&!3PbzirK*&FJeY7K5-gP7?34zUE0;V0T;I`Rcv`{SqR49$S8@rY24970Z35xxgC? z>l2M%@qOY`yqv1Oe^&NQ1u_Iup-1%*M=BIhgErO;zS`Q$AxySp`I)hww~xO4w7jbH zPr-?Q_Y>%A$s)cJ)U@xRcME_BT%SSEhe4n%p^YIrjv$a* zhw=4Dg}422gyDf!f(YE3IKuG2J19i>_fbR|;o`QNVD0$Eg`tfj@I49Sfm(=WcRaAy zhpR=jkHB@HRbColpBRh7lbRHv*AllxvvS{eGvE6NTXUEU$<|S3jA$RBGw=8t2}otToHmoWhzTi&i@$52 zb2$2ok>or=jncoNcaMWNCdkilAcX!2-5c=<^V*f0?<3miGjuhM%&RL~v6%0DgzeCp z72;|Wq#{^IQrVT8x%4{dt&RkKaUKSNJxi;rOCyL4?RosoOq2w7GtR>y=r0jCtsM1( zXoCoeoOsxdppnEP{tu~a2Qq=m_WI2ChKKzK>9#Na7Lx5!@VtBDBW!)1KxMlW=6fGu zZP#$e)#Bd75h1M{D=$P~6&6S6K}gj^yzheu>;d@*Tg4lB@jN2hN7y zxf>ot;Au99(0uBZV-Em36NvT^q;pz*Ue9U$?nSAHhyD${6NTRS(md=*P2gcYMiL&j zzb8p5jIRki%wk9?+qp3aq{3{#65DlPR)h#Vk3Pcgpy6S6ErFjwgb~izF1=ZiU{`o= z6z8D_epExL@O1eIJm(n65bY!IoTK$!8iAP%QrWX<*5~uUtj|VEp4Y~F1ZI861JOPL zZ^lrgi1rcs33-NCUP;g^#StOx2W9{^hf6@m5qjX~a3~38XFkG8m0%^>LgVjs`Uvz_ zxCh8DjtEIAyMsn{^r%S@8fr2b>c5&!Gg46|NOc40FwO%Jrpsxm%ox!=!sb3^0* z(1MS!wwrM7@I3kmo4pw8v-M7LOAI4i=)KX1vXkZLe;c%+C4~O`0@i*Okgto-^yK0EAr@-v2L4^8K|N1@==S8%Su&2n(h4UsL42*baON_r2hE)1Q z#s7XZ&O;CUDix^^ZKscbPFF_nb{)xg(85CR78&QY*}1XGIFHau755DG+!-w(I*!l- z|3o1bdI=w4Ej(dfMJbO(*;7mTk)~^W&TjN~hq1Qk^p+L`&S9X_o zMYPdp=)LuV-XJg9q2k#RrD`P90y-XO?}uwKdV_7T=IBp`J3iRVPo?2d=c;mlk%Z!_bh>j-HFv3AC| zloX-a#1RQnVZ4e9%IE~M`%Cj6ywf65S$i`x`8?2eZAEXW5bYx{4&o_FiqKGF zyYV*%kP7)39%01EoI(1(I3(-=+OdzYd3yo^?Kqm<@xXmXTS5ta1lpC29|^nZONBid zz0cBRF9|$CCzYi#J`rQar4hC!HwLAw|eBiiUQ P-e*YAkF9ac_l*4ygu*9@ literal 0 HcmV?d00001 diff --git a/kuka_kr16_support/meshes/kr16_2/collision/link_1.stl b/kuka_kr16_support/meshes/kr16_2/collision/link_1.stl new file mode 100644 index 0000000000000000000000000000000000000000..07f6d285cf4cc928a8aeb7b85bf3b44551a71d78 GIT binary patch literal 30284 zcmb_lcXU=o(_cy`(mT8eK_E2gC3Ge&QmvcPKxjVm|t+O+;vyZK7)h+b@`4^s&vAkU$xK}1b z@*QrNUA6CGXUO@yzNOb*`0Gav=GC^=bLMw1&GWyG;3q~!@%y=#_!xW7X=V2xG?QPR z_Ry`@V;nC$`3GNyPBYw-m)0w;PUrJFjj9~v71OP^%6I$HVXVoMR`$L0)A-?5kKIGV zCh+407Apirn+PWVRxO^-H--izdE;0%;C$f4zdTnGeU7yKUjuS1g(j&$>TS>bq|f>!!z`->G&+Z zGgP7LwJMWntTw(0bu-lcj4xgIi6Mj5OVNypjOhjZH;)&$d!)$c+{nGef%$;B5v~8D z=zb}}+^Ub>cUOEe#${~rMJC|C=ld(E8AL9MUS4Y;zrOM-r%;af#3yPWTO$4o%q8V#fu%>`nEPkVyeg1B^JNNcZ zD`WN$m-d6MH^$0u5>{DO+`sa6l!#9k&9_WA;=sC^88?!DnfjKZ=e-!{whE~3d;B_9 z_I$#M-PZK4bNEjtLQpQf#uS>dX}1I7cBe1ngzt?KrzEMaD0+pt! z?~M5tmbc@VcH;0aU5PobeXmyd>f1Yfxbly*{*T-r>036mYZl$?ezoHtm-Yizc%v#) z9M}`IPmDeNG}LZ;{VTUZwN!$(mm+9QjHUahoeiV=!`#$jfN!dtQ^uelbQe)HV-;qm z_YIrzIlmzH2i*r1BBvzm586M*{%lo5jNcP14yXBq)74O=enq!Ovlj04MUz~*dKjyJ zI=!0n!rR*zEAfw4C3#rY52Pkw+??~nnNlf4)mtCiu$DmMz#63py2cpmw=Sg^n(?Uh z=R4uX9!!kDni$(%dyrU`dojOLD9Dl8$0gdwMcq|DMU1<$!Ct+trvFq^#9wW|{T~*z z?Qv7w_)6ET1%)TLbRFlZI?;XIa)R$d(TQ>;p8K_}9sh1l?t7C`CdRRFqnkQ~Wlhtbg^$E^eNA1yxClZ#%mC#}!sIt%YNqIHnlpG~P80jswTZ4c6kzNqeflVE zVD69At@c{AEarb9bqO64ilBRwv0vgU`|cL#D?S;&hvSICo{)M)jWp0zw|}PeE}Scj zO$zC5jb7ec^ji^cAYc!IcAl@#D4@MlEwplRU!wrmh(H zVP-pf#@)`Z17qCFuVP#{uapdVp6AH5$JtgR#!Vx?Gq$DKX7_r2OB`;L%dVL1iSwV+ z!`yP$OoX`yFTbkh=06ZA)|6ht&wU-~YAlYD>yR(Tt6o+)cc`*?>3u@erp7sYPATqR=X;kEPYOvZOeF z?G$e?prG9=q=&nGd>#(_ZqVG3?$u4V6vFIB&YE?_n!p9tPK*J9Ufm5P36%h+!!|azd*WO@cr!b6s_Bn%X{Ept7Ce z*dw>W#p1l>#*aCi0BpH{u&){W_0t!8awNAO2ig$clV{Wz78YCD=vyQWsLu6883aQ zn_cMYLRV@spVVXuLD42+^N_v1+*8Ne^KMsjw02I?l3zjte7%FGsPByJ$lS&jm3#Ah zXJ5H;C2~0FVLtR}kj#00=1m*B?>)}9oMnQZ`V?(i09Er2w>F$@;(KRBl%Tz({g~H! zq+5B=FWN3C@J~A{KCpvt%aKzi?y?7M~(3nN)sTc-A2(SB1Nlw_P|^P?84hqi3VqC z^9zABRIB8v#^tG|XmjoE++5oJ^GPbZT%EK+T1Z^lREkSlNL*TE$slr+uWheC8~Ev+qpbjN{`B1m%+B=HjR`_WIpB&Y!(jJJb4%fu1K=lhn%0 z95cc7J!_};$AMlI+*WJ-&fS1fg0_lsQ8Z&KhMjVL zi;NZ25~f@f%~+e?S2z>GzjVGFXd)<=TnnyT3$8a-KXsVpWcz)t(|hw+SS1N16oGb- zhxjMMXz_Wu(){?qx`u@;*RD%^5p{}si2CW`zAL?<5DgcI$+?O{02mN&vr>&5dNT7u`i*Q#T;hKlzFPvo;RT{94r3vC7u z@ypna{87DL;$d7buxsHoPEcbiNu^$**`^+x za#8f)P@&MfCVu8)Z1bz(_Len$c$&=V3}1g;W-rQBeQQn&_qnGJ&$Mr0zdBXTEwC<~ zfD-ik^=Y8|4}D4~TCS4u&FsHQcXj8^Pb>5(qe>`(*2Gwi;;rmei?X@5(xf+J(0aA* z(lQ=gX>E^=JL2^DHXVAYszmE6Ka8j;<5B5$cIMry{qE5KLx$FN3L*Er991v=z}TG` zZS8w2M>(Yzr9~~OxG2JuF=Ij;uim()*mb$NF@xu0e^ld^b=gRtIUjY}`}y5!Jw^I* z&3Mrh=Y5k$jB)qei*YG}&L(3&9eBbg%;_j5#H{h%jXj|1W#O^b#zXrRU1sgmn zyiv#?_sMDSigFLV#ZzbQBBso_=A&F^H|_IU^)kE9M9f_$YzCC9H6&Mdj*oVD)&qWX#P`{$;O1ofa#j z1m&Xf0BM~$(ni&Yrzh&TWvjLk&%32i(J1t=srL)1CXeNO#l z%0porL6JPbrX;Us5XTVX1XaZwbey-|F`@6fyH~t*V zxr)8QDuH;r8aEmJp#5X4+Kx@myN4r0`HyeFiUaFT^^l@X#IFM*{h3ns5-IKH#E7s^E{bOC*tv>M$#;8*dpXU1P%hdh8OvCI++F!c zDG^q>pb>AEew!=(Hn+^a7}ty%l=|#v_n)82iT)?@8?g+Eps^FiI`j?}B^#9$oyTsq z&@O?|Mf(A0jKg{N2Ho#h5HA~47U|9(@=-3dERrHl`GQ67G&A_Ak!I9@de|~f?aIi# zj*B{WT`?$niEqf*KqHchc0%H)s*EA8tt)1v?&%vfGtfrcFfkWJGuG#vC4RbLaZ2C0X&*5uRa4j9zMfOhUE3uNL_D>{p=icxy*Es%rCj>7Oa^iFW>u?S z_kO;wK9i>!@kaHDqY$Rgxz(4`I(ul0uWMA4pj;HKPX>i%tXaOAJn-T$`^uYQF0G5A z&3;4#=HTltkFw8+GY+kba#6I5EoJQNPqA{B@557L6ZZpRmZ~LM$LLm7AG_SYBj&Jg z-!c;+TL=+P#U*7Vpc#wnb;hc=;_qsQ{)j@`M|qIi_EB`^#$8?erO+PBk`1St+9+f}h@u651+OJ=FHDqA8lO*%7~5E8a|x`y!DHY9X75BKt2`y(T{hu9Qdy z<)Sel#xjrj*~))qOWYwTgWBp8LFF-4s_aE;SLdu&+Z$1MH=){2>!oOUKvmgiE$jX; zF5u57!#ALIiHV2|KVY@^@NC@uM6IHpg^5@`{(?0q-N#nht5JeR2PhYfCdixJug+WF zwi#kwxf~^Eq=0f!G-FlAoU&T3Sz+ZoA7#WcC>M=uFt$41uh!C{$E=Yjq6CeR$nz>8 zc0$pN{q7Ui_Jyf@4dbH(jigd8GcMZX=j~R7beViZ4nzrBLJ>5=%Gjvko2~wra{G$x zi4rsxO1UVSv9@K_Sli!!&sS5J2+Bn@xV$Ahyu`ZjNXqmhh#c4U+_?pCO;i?oobKBrt1%~DV%|Ueg^|6Z^9z(FGF#QDL_@pEn@zlKIc8`E%0{aa?w{P%GebN~EigHmjVMf{ zm2y5Rj}!<0D#d4ANzJwWscdI?CaTC?(mSu&_dc{&)LUvbPWypPvrtwqnXU3C;zLUD zkyGX<`h&hDq|Z6JWkGxKr=_@pU&VA+`jW zau9)n$P~~JnZlLm`34__4YzYl?82Le#H;ufa?uE+iKtX8g}rZixY#$Sr4gqB1Vket zW=SJqjD4Ijw>^JiV-fr1mySLMUD!EVb1K@5+_lO)&5GzI{A=Vsr?v=1(3)f{Be0D9 zes~4(N113>>sL>Pcb+FBBgOPZ*6Hrc{3WDisr8`ZqG&3cvCoJ4t+000{Jo{^LrZAR zm9|k-P0}uTy4{+)CDdOC5Z;Z6D$zSt(X=LcKlq@Y{psd?ZtMEbTskHcP31ARwOJi| z^o;W^Pkq-l>Lv1MO^o%~vfc`MHs1f2wDhTTt#MSVv~Jh^xZlvSQ(es>A~yU889Q)4 zq)I5ll(FymQQqJ{H_>H55Z_&IuUZ+iA}jlH#{Q(}PU*vZ+WJrtR>szSw~q&v=ppL8 zwm9XYu~!rExLPl(Nrj7k`-+OgftQ+OM70&A`w?FE7T=${i#QT--ACiC+V)Y|DQ4_- z?%d-%qJKBB|8}6!584unmKk&lF7O4px{A-&W;76#i^^u~i%jXPfPd0EQ%)z`zN+?O z^c40AohO-RIUEt!*_F8lsvi_Vqo0hG z?N;1zVxpW0^_7L}%8Uespj;T4@?=z+Q{A~eae@<2)IlTv&5n+m;H8ED` zooR8et5tHo-evAVj6i}6j7)kxuk4(TduMW0r*WK$eyDsXD4{FEM11vpfZMR&5K$pt zVI!N0MuGKBwTfRdHf;44|LY~;PR`k8&oM#^^5n`Vk?rZL=J^+_Zt1LD7$s-~nM$Ds(RB_K~u$zyDLoBkqv+BPnVhWRm@3VM#QP@t)78M91LMNDja zjc>32j*+({PX-rm++nrT945xDhP-wgZaBfK7q1201Y~0>>C)1NY|LbO{_teHJ1JTo zIK5lrO||0EvEF15pNFn+Mf25sR+k98cUD|leoJU5lS`Nu#b>mFML{h-ld z=^LcWCnmj{!anzDpiQ~3Pe~CYw-yl@FD-Ld^r&RScjZ~@%G?GQ;;{0pbs(*=em(zHBHzPYi#$+HTS;@etv)7M)qj$JpXMf=2+|m~!MUbVZ zxF~|&tIM3bnkhuOiPxRK3VaN4IJoau2+C#3m{Kc;h(2)KIkvTl(JG2IBijX}cbXyK zuK($+mHx!>Z^&-jcw|~a1|6(?##&a75@j04I{N|-SWp+{z#$sq?HE-Dnz8+_s=KoX z47GoIRL6Kxf$>&YB^ZYVny~>nvb*v(YjsL#8~NXdO9IzGxN}#V<1ulT3?k=d8Ujto7VCdCwhsl z`TBF38v$M;*dpLHN_0Xl1!G6*t>8hEdW&KCh8iUlp<_Vqz0`11ohp7Rzp<*Xn9*j6 zVf#=7wSySDSz;!i^KoBM!Jv12Qk($V+s4p7q8sKld>yM82lP|k3kU~9_&z- z?DHGzWF|+4g}ZsVJzd1%(8)&b2Sv~kk*7hYJABfrrs9;nh10qyf@YD(n9QRO>@GJi zTVKe3sec~v4N4;=)x1F}Q9WnWdFXv3#@XslNddQ3wmakE^$yX_D51; z63Ru<^2OonZ>$P&pZR-A-aJ5xA~sSM$~}zmZBNkn4`MA zFgCRa>inBa>!Mr~E#DjLOl#*z879WGinVBTNZQwsRjzyvL_oF#W6yE~*r}(t6Mde& zF%Z-zr)U{lx_6gLgd%87j74{!!;3Z4_5{D-Xw1n16(enMEudS7B z!yo>$GQLaOi*W{!XUe!%ppI3t;Uj}PO(l6y>+63C@nZoS?_0K3;zTth`PK=0o#6xB`=hQRRew1nSd2NgZ0}5iNzt;`S}$Ejh9GL+d+=F zY84`2^)R-ud!S%nJ>rq+0&VJNQUo0Z#x~Vx;clBSo@d!Mz=#^iQw^eO99lwS9P<2F zINq%=GnRk4v#M2Q6-H%t5<>)&@2}Ph+>>-wJ>n>it+2G#kH<{BCia>wYLtI)A zC~Azqj21;fjdFv(WAc%kpj~{xB3Q(Lr2dz=?By?VgM9vBEqxOc5W{nYxnIG2bpK; zJr1lN>J^*XC(Zs8_L^_P#p96d7M|yTpr<~b?Os0hlKL6#p6|654<_A@Lu&$F!XpB9 zlsrq|wVOV1@@AS~h0Z+aUn%c|sYa$;6fIxsl^kKc|JyNtjLc!dRzbZKZ6fqJXcv{| zpgzgeu0?&W`vh5<>N{h-m;d3$77wvIF8_m5eJ<-&T#(CYj#ZO+_uPO*TufIbCq$bQ3M?k#&l%cCXsEW zo%LCpmUuGm6#qcf-TIto+?g6O2NF&%%0fOtuyNd7bUU7ff>G~)aMN@q&U%tE^EzXH2&X9Dw zeN@Y!E&&;+C4gqE;d{fx_s2@OwF@;dG#ur^NTG-LzRFFv_&sxTo{zXJ%2}nm8WKcBJ9IfgH3VVn@f;ar1hf z7=iD+5Di>FBU;YEwc08}59-oc-s-&5t#YAN_#J2yfn1~?2ErTN!gsRBNEwTsd@4%i z$v{jOep`a(%+TL}k?}-=pf4ZjZ%den7T>2-^If}u_nQMshWu>_c*lUhy<)y;pa{xE zUyPW)gdkg`#vJ-VTSZ%9zOL z4O=W9P%_E>&?mB*L0s+L+YE|8E|^=SlkSgx!v~2ORTis#t}RQ9?UUkkL zMbHvNQv}eAoxc+$mOkFAbcVjWQNNdfG_(*cOYfHuC<03ob5XQ>_4{muhfI@R*582Ca+s9ObZ8WFT<~6)tuAF z4enr=L8Lty6oDncMbSumn&G>qt>vu9jHi|()vt@e9)uh?y86s_UK9Z(uv6h(8s(yB z#$GP?LCGllBGPynMiJ(&O^g5;@GEi@L1oL^r5{hZ_e=CtW2H|ur4#j;s4|c6yZ4st zC_x|>j3UzH6je3BD8XN}l7ada5JR8jrF zx`0btVQNJ2yVnnbh(<0bpo4NHnP=e#tyyVM{X7k>zDc&G;{gw2zpyg5wxZR8Iq8#BKcPoK|OD2k)pcVGUWmq(I$d& z(HGJ*2U`BVPo}*fBl=w3zJ?5%x%_qneTAJEfvsgMuA}!Y~GA& z1WOK~>}Z)CO*5q#3tK%FWU#%1j~dz0G{2eNY`q;pxqt>sA2Oxo8Fj|_5`ri;R&ycxlW^!!$J)M&AUbD99^#F3wRYF&fjJFd6<)SU2Eo7|k z?vkR*VjITFIC1DHqvHYE0w4&6Tri@P3u#YN-wZ7zX3Vdv<^xM$6zTmJeou-(uD2n) z`Dl9}g}A*YT*=Te67?Qjd-SU9NJAV&uHAnT(G-C+)QbpD#>;zm-6r35Q8Lhuf)b>` zrZN%FC8Dv1h{h6-j&x$Qys2Kh*U|Q_VaZ5~RlVB>1hr}m1WS$!Mijq$qnr0>4!3&K zF{&RruS@L@GrDo54<;m`w#r? zMT(#wi4jmj5lDN8H`3>fc@_>bqP1p}w-U83 zQ8Kj7Q0ocfDA6>M5Ub0BHvq0Db52wIXD z0rnhZY%=CAH-&%u^-uxp3N04sA<{4kG)KontWO3(xsdjLJ!$Zx>T0Yy@DfJ8D9ul# zt(AG<9)cx@fVM*pBt^??!&eQJjE^?{$A%K*qB)|;A{ZcOMkD2-XvV%T+EL9%$b*+g zMkCFEr0=nkBA`|HyINp>LY}4h8(W#PwpKDidt|g}y|jg9t0;n&(0XZ2@^wx59%`)G zTtBD!fvuvMnKWb5M9|k~i4j;6V~2`Gs(u6eg36#=6wTP8?ZZ_+ z#t$55_&C(Bp?RGqg1#~X1hgGIBoomn#bDKsQr8w3{h+N%77+~yDuZ%Sw0x^y{7?R- zdxU^JC~d=pmwI@U5Bm|ndvUmI$snMFB9Qj-01Dh+!%xT@FOVUvB9&tfdmCx6kmMa3 z{0^+LgXB$|M4Z$JEP)(zq!Xj%y>rfa{Nq0cD;cN(pzRca-#yJh5y%BHC>MSQc`9bf zNz77>74%$MfIj?1F&rxoA!C;R6#+IQMJvma6I(Q4tSA>9x8xD}CO@H7hz5D;RO4t< z%Tp#H!%&`TNiq+;6Gxtd2?*qZ5<~-y-@Ts8)0t~~7p&KW{6wVxI|A!U%tg`i7if;9 z6IPD83=|YkiCHj$k9L=WXoSlPn}t;d(%>_D_VjyAoPv0lJ|B5 zdA+($Slw^xF|ok{sGY^n1P9?e>k@gVAzTCuC;QoJ;(k6oFij z(TFs(3K8B|ZT@1bdv98Q)erQ3pe~BQ@19pg5tIvQkY^%}cc0^aC-Zk<&Z%^yL7uc9 zRJN(t4}xIG1?{C=NPGQ|5f)d+WTLeNspb~BpkDm$$)E`2N-P5ro{R{8N3r|2=Nxn* zW(YtD=0H-~lkvY0z=bt=h_8o+iP#)zZID4TQcwnP;dif96oFh&Lb>p}Cu8q}7UEEB z7BwIACSN0xWH-u)9YG)$_#8-sKR|0@Ot(tO(9&H%APoqLHV_QC63ajYd}l0ROK7xCqXbQNz6sj(iW9>!ZWKZ zR{cO984yTA+p#9E9~6Nl6p>gSj1c^Jc@ub>0jmUQSQ(N|$SL&r6C)@WrM;D?Z^_i! zrQQ#%7r%QeF*!uydJ*j*pk0TjMcF5Q9%THo335S8XvUt`k0Tl(xq|Um{V2kGQT12m zr~Id=POx?vT18N=jH;;@5kTX2&sqY+?*D>-wo|n9oj%H7FFDa#$)NFQdBUmJ9Du;@ zUJgqgiCC%;$OSDynj*Yj%Lt@>OUEp!bff`6(JE${EP`?&4YCtXXEo=tBq6s_pS8+& zM%v4|*A{?6V2SQW0vcn>sV6fIwKNW0|6-=4$y5lv4{nr({T;bbrolnZI#G7%MJ)?|s>S3w5aKI%Nj zQxwi6q&*qQA)o|hBt?{xzg%DN{8JUPr14LE!>i6${O+BD6oFhI18Lwwgx9Ji^4|G= zL}@iv7zG9{ioowl5DdAXgmU3`uT}cyN6k5EGVoZW-i7~*5~q2#-kj^(C51pPC_yyP z_}#l*(zj#^K{c7a=TbWgzk4z$f^s1ZTqZ)_t0@_j3u#!Dn2qbnNDe`{DD5G%uclJ3syx0_vq`nHTQ)YDxyS7g|EO@VnP4ia;(Xp6>Usn{hEuKju?YJ{vkSPG++zKQn*2W`^G-}GMB2Xoo`>p5vAxpvAM+HKG^(UgcI;Ty!rkKZ|Nw)x`8 z91ew3=fZJD+K>5Jm%BH#BkZsGKnH%>nXI(r;P%MSfxNkzngjCm)j*sQF-cXin|7ZPV*lZSCFU*{O zJwNSHZU*Z%WQaL(sy+QUX%>r}|I{F)ru$62ZR{vMZs=F#4n|ZjU5d_VGLg-Rn<++K zb#qSr!^qaWU`TO}?_dP(n~=Kk^;m3xJCD8W!STG3V}iNl_K&;XrNGZDA|OWeQQV=s z?{qVcjotARm-96?W4$7U(S!t^xb3^j=Qe9RJ4AUZ+%9g3z`v+->5+WOoh!zZV;%Ic z`9HHL@lF7NufIRl6ptakFKu6tE4^2>ee(SYEg#Xp>8nGS!S`aI$Kq%MPtI-vDn4ymDNm0wXl1-SD_rn(X0Ka{qTA;FwvfE zUbtAJx$4u9!<5~n3$$MgG_d}jtJpj-6L)zHqu28v(3^x-)dK!(O7oQ|#mJX9?|^xY ztQAE_^1jq?+qK`W2R?*sj2%YfC+*karC})rEnCX5HPP0`HPJ`U(5mLYB7~IeBkI=& zNrd#+HiUM4wOF6fXdrvKF7v5Yj!W8psiEzuUT-(P^=I{weQPUP<3<`w+;`DJbgx~B z5rL?&M5p(6)?)D!bTh1DQwo2ND*uP*V^^iex(DgYxmP#yo9-*LBoWVJ^$Ug$a;K?X zJb8n=HIzQ!Nv!_Fli-#Jnb+T)-s|DX+4CAKq+6zbP3V;bW0Fs(A}VL=t=GCgo=&S< z)<`W_l-At4${a8wzw+MHcXe!R58b6?IQ7|I$``*~jFt%77ktJ2>4+6C*t_;;lyQ8u z*J+{4?kv7YOB260@jbX5omaFwub-Zc;pdg}Dv#d+6OWG&CJ+q;BI98;{To79mTyuA zdih8+%t}IL=i9{scMs>$XZQKab=PkGQ{VVzh4fF=qFM33=4w)7^t!u3AfCAS^FQ;f z(Cm9~E2N`crPIE2rum{<3Y+p9;--EK*x zto}iJ|7EvzojmxVuZl<+IEhal5##LBu)jCo^KOgYsa`1sfu%}Lon^hZ3qj)r!g1#lR-$zuZZ~0`2H)dZ zv5E}7N68_(%;l?H*zo3dn$)gf6A4-4P+BXw)sC;}+>_7fdBd_3?xBNCylPd8;}Y@O z*W>O>cE>wdL11fu(S(E?9qHZeK_s8GAkDG>QtRXXu$3U>bg{15lhu*DNko`|d&l+_ zqrcDg(6jptIjh0HlC!H(>@R9TWXy)vP#J(lr^km##d5;jg|%&YXX2^A z?*h9k=I(=AtcVf9!LG{@g3c(}Bhg&8t2`qgRwT;5!&@ihPReDy{DRWPnwEBPaH?Z9$WY6D0`uPpxsdw`XLs}NF+ZcgcBIL-8A+(g^ zO8wH8&J0Uo8?N?oD4yBX?I6H z)5kCIv%D9-w)wOPCbh1oJ$2Q07$H8dm53JAbr>}m3618lc&(tfv zbX%YYGx7v!!jlocPlE7$F5RhNjok8H#KP83g-a55jAwW~cZ?^;&HS4z&j)4T&Csxc|n@5w2=P7hm*E1N9bS;qY0VSxosVYyrS=1Q4m-PuE7q1H%Q10 z5#7a$=+1X`h~mj$1RfJ1bA$)rBRqiH-oX^#!3g|>glrKp=M)ihj^FW<5^ZCIv~V{6 zs-lQ%XN$OY@nsJMA*~EpAB-mC(xw)ycr9;!u3Z(1-y)X6XhITKbmr?G%+Ot~zSFUf zJ1%3R+OQa0&f?1u}f!KG2q3duLTSeAv0H_|6dH?DueC5aZydCFHmD zkC<1EzI^=I(TeAd5vmvdYqy82_{6?^T#gP_>?GU8?@jGvUt7XY)$YN2{NSj+f3Vd2 zrEF#9=GfVa)y52}#2{Al+mdSZ*rKsACHIPvd%yQ!ZSusi>dS_3`A#hVQ}A%nrP?sy z;pE6)yIeB~X|9!Had|ee7sZBgVC$q5M$2*7ILpazpRqhcf_d2yab}^VTg}+eiY(9U zQWn=I(JJD_-Q%X+4Nn#kAFe!=YJaR(HiU_iyErL{@3QJ+M;EX^loR4E$7B3Zn@rb$c=kZnB^4-q4>%ojsg%?5jU(@=mbi zLUY0s9xs16%iImWaGNcS3gHW`Zb`yXO1lz?=BR}7EP2xUB)Ot&5zC6Jk(P!l*4@Fx zQWy=_pzR>uA!N0PP(Q}Uct5WeXzre3<1eDF6)>`*zaxg1z0Ef53gL~`E%KJVTii>l zM6=MI@+_)KRUh0RAuH}h@jF2+W-jQsRqk9KBpWs%;^J(h_Nw{*d`M z?#n&rg_@mj`bYW2oZWuT>A)nUvu7+oO$kwjz%gq^0%?3I5n@-5Uq-m4TZy+!jWw zh>tEG^zH3>bB`Q{mA3eL58Cy8Gj?#@O6~A(b?Do_{n^mbtHo2@4f~`Yo)*9t*`LvH zWQq}LANe0m(T$h(M&Su#={Y+O>s^(!Tcfm#(S*3q-lcyDC~S<}GMwT*a8$f1+0$xi z*8Sz;sXFB~^lSCrCtYux?jEGv(0am{CsVpl|dFrl2W^+P00Smt7M^NhB%<&h>)id3vN&icEN zbGAuHdC zp52Le+Ulr$bIgP^U)_L41p2a1JVUk}gw|fEbUU&C|Jr^oUcEzWmWxD1TI%nKp^^md?YKf4-#1$0$d94v*=gv`uWTH7e{ z1}!`HR5$<}_e7K| z!)DdL%FZ-sLUFs~(|aRezYm+X?bj@QjQ)*q_ha38)x~9$cunw5L?djl&|oVCJzs2Qx%qpS0TuY2{3gOw@1gAurI!M6`-ZS?T6vKdO9 zjI0TO3K7V}!FPhn5y1!__B949KBBw!%2HW_s%bEqkTQug*{ORedj9T#RAFw!8wE=Z z-$P|_YVFv>Jm#L&uixlFl{*Ll-yhy?jQIZId-UAJn(8Tfcf0OXxq}dED>+(k{m=BR z0#R>7O}6ynX+77E{jE9~XbV`5w3U->PZfPg!<-W#Er0iCy&;JOW`r8i2mjGAwq;rJYaUr#7rYL#U?O zTCF0Rn{6|@ux%*C><~dx3YzH2pV{8=J^8Gt0v4Yrc^G)RN7hmXT%WQYN&b}|+1N|H z_`Xrub*vdM0+>nJlE~L)++`K#Utm7xTTMyR@EN9uXjKlTh8;MQKzR~Ui&CgjWb z3|8|-5YOjxK*JnaOuslYdRay0e9%eZ%LwsFdBH~Y4&v)_CTqZpmapo{fIY36LRL`Gq!Y4FuyokWYf`C z!wAWp*s|e$-)&(NnkTb$_XDgo2s#5+XL9vs#))lBS=vES1DDA;9JJWlyg!AoD&D(U zN?4e}OejoRLZPGw`C2jec8Mk-!($4M$tFt|bmtK-!R-v2C!!Ikcq zy>$uVSPG+o%Q7D|VZdb(GBEfx>ku5s>+iW>Vky5>>&@#kU0G1cdKUZj9Z{p|YqorB zAYXRlyn?{*4WmVL*C>Ej4%)|#9FJ$pI}x=pz>DozxKeo|gmg*i%Zt0NU^y49>#+m< zeqoro!BPsE>~1@n2YCHqM(>@eATS4n(S!_bcF4#*?wDTr(IBv z+4}q0+$9=mN z8o}+NC&4Wdq7_PK`QP^Cnw_gz<@y1Wh5@s^-oP48K9!9N-&E`Y%hj?U-<_V*#B4T3 ztBBI8#_^O@t&(!o8pW^_)||LM!I#`}GX4@ib&l)16R{r+{egx9_FVlQ#Zt!e#bcwr z2OkMk`oIY21JJ5q@*aAO_r%8e815ZQ;WYQpS%28(uC*X3a8)VMs2zyu_YVuevPIw!bNj**E_!XoYc8S zxWa5>gvy@3>FlO|?v~vs*END-h8`nuK7kP5*KhSlKLqlA_VEg1ju9%~zSixHUU6q2 zKXq)E!s%lK?wgS1p3cUuPmz=~J(>g_0DLL%Ue=Y%ZE>N=f95sEOv@fw+BaUm}*m zXgotj#zgRN7k3=jDkeT*l81weamlI;Z=27QtQu693mY{(P#^hWG%b-*lU4ssw;1d= zKivcl5!h_M;+>VsIzoO)YfYb2?QZ-s+L23c5~{8N4Ot*SOCBC7*9p13p#{A;sjlI? zuPnz>7%e$V=ugygMs%bv<^&tA^$Ky^7Dh`(80yPJW#*q<=;1bg#$>;|9N)nR$tTj25^)_`6%Nd7_U?v*v5rA2y~h{&3;gH;{XCoNukm zk~f$&uBh%^FNBs`dWqq>KFFRxyKC<+SG*`urT5NBAGbS{exCEE@>CdsTM~O5L_J(L zsE2zzgMF(u6LtEM9Zt&=WPNj4voC7ZT9z=TWkk{&_17uh5?E@O$6&*;XCSIYjutjL zJ&L3kMjth>Cxa3AjfiaD$78I<_A~lS`%WBt7PwuE7LoAt^(?VEcjn-|EdWK7(9&9{xbNm!Qev3{YG;UqLe zwup=*EQQyjI`Ut3IvE}Uamej)5|+YfRhL|wUWt1hJgA@AP@Q8hRq}Agn!P5@?+A9V zf&+Iic0}L!f>MPy6qN(u6$3At=KP~IrYSEVKbSr`FW>v-u%2Q^6$TQcRm3W>qSm+f zGhX`TrE=v!CPuEPAU{1zR;J9vj`V6wun|(X5XDk*1w*z^u1&}S64G{K3mPIc!!LWw zD)|qo86d-lTOwqU&_1aZyBn)UJ5t;(mcnRJ#d@v+{kfYDZ@42|mumv*LeJLqr720C zEWXD;rAkv+&Y7j@n#qm%xrjg|Z-5bMt|(yXNw#tIY5h&@jtZZMIYjAGTl}@4VT$mW zuQl0<#Magq1oi`%UuQR4y+_3_2NafD@QIf{GXIOI%=Buc@YD)IWt|^}a<@J+StQ@0 z<6Q{~bCVg@+V+^N3<>5(S8Qb22JO``b0fVakW$bjxx!Gsuupro(qW~=S;}fE+#g1Z zSS_^&zgRzs9SAjadEmWXk-jODvlmN$Pc8Kv}r z`AZeiWQ0F|JK`aWSbtgJ^l=|5JDC4`BYv~xD^}e3wt|4&JUg#eX0V$FqecFFu*M&! ze`GtJJl3(4-@JKdhxJuh+^-@NqkNBxlk;dj^NgmGn=aH3tt)KvMS`~Z;2ogqp3$pm zowa-3Vf1?6bIP7kj8+jLM^|V$I}E0Ozfab|y92uf)d?6OEgV#Mh<%WrXEd))!)Uwa zyL4%npb7yaa7$uOL&f)6hwVSn*CLRTwifpGVFYf8kemzh>$9eeq?NpXRuIx6!wx`< zCM2m&8GYjWQ8fB%gbukh7zb2AV=0UldozYt(a*Syp?^;dRuEA43}~o`#%Mxv?Wv>t z6dOy+uWGJG_V=}7c0r0h$^ka7%=2I@DV4A26P-J9Js8=9hjV zRQY2xA$C36>HU5kPq(%BRl_-9EQQgcR;^%1{mZlQ^yebc8qOAD1a3*hgAY3C^U8(O z_!z3;T?rV0TO!2&T4(*47EafU%J9Vq>>**asED7IWS+13r(P-dK#KEDe#i1yd7K=J z6Rav$ncoqWXM;bOdrF?xyG|HDu@uhfNH)q=_j)N^GmEb}u2=CHr1SyYJNQ>nDT`Yo z4Mnv>W2A4BV3&f}$xfBGJQe%V2U1g0Jf%vD# z5FcDajS;v%@jX75G1?16!o5X4xB?p^a7%*y_@RuETOisLKcFCR#WzM1Qt(zOW3%v< zDqXqcgZDvVDU23uRG_0#RUjOme^wAUgNf0i0(-phcZJutxLQ$PoX^Bk7%lc@6fI_K z6O}b@>$)ijoN>iyLLTKSY)lmlvfZQfV zVE;kn=r_Gc8uvJox<5axARxO0XvleCw8&uHzL*quE0R_j`N|j1S1g6mBKvxHYm&#A zNLs?DoH9o-0=FdgZ6EMRdbm20dMxd&AnQJzadlkr=k zm|v0otlO3TN)0{myWlfI1-^=i-|~hTX}x)c-QpAnluLuJ7PO%;n$y-~wkQ z=N)HHoVzMD6Bq$8oXpS>QfI|>*2nyfO}O35%5BSbaepczRaBVvy8bpPpk^eOHKI@{ zCo40H+ON-2Nsg*N6{&ArkJ#@nD?x30Ek}#$&p=WA`D5TF6HDPfB=2*%Dsafn1-Eox za7%0L<4ws9MZI5RO3rH9=+#O~;w%fnEjbHr>GZK(CT0B!?RwPHa(EHUF2 zR%XdL15C{6L*)HE3$Qas4*q3%7e1$EU50Z77_A~!v~%KqecgCS$5RTYk9qt;$0nO` zH>;Wp#mOy8osG`IMpc;_E2C( zPcV>C&PINLXtrT}5|+ZzJ!TCFssC{c>(n5b^?n$j-qn(kv-Tk;V_do8)NFi>Z()wJJvgTW^-Pd`P0k%B#!;}nGheXs3tM;4Q9)oSHCN<2s*nES zD5o~ zdv_d7D!9PJQux`WPff(hBtl;8G`jmfuL)<@X^>#xn2y z2AVPwidr&JVO7P7D%w*Yb9fYOm$MC%u?#T37_Ij4px#aG)%wnKabpKAV@r3tHKvSA zfqPYXxIJSW^hyrF^hv%)qJHo@--^*HV&UXsbj+3(JnRpDChLM@7EUxJ*E78Cs4ORi zv=BAI32RF6C&}BC(@11B?$RcmP02<9M=q*ZMUC)YQ6t>__B0pPwl<%r z5sncx!WY6SD119csOqk9&mfj=mr_{Qs)&-oz4@}#0eZf!w-|00Yi*1cIj^Dv`N@!q`mEN>sxOfi z0HalFpsyIokDgqqT_3oVDRo;XUJGwvVhyqekdPi_SjEQ(**di4fN+=h?$sr}Zh* zY!!6y&4Dq+kFi*w9la^e0#SsnQl==oK`HFIJhi zc6s14;AKN9nSZDY27VW8J21kStry;Fm$v*wk?X8N%d-m0neMU9j5*@Ua^&+-_Na>7 z_JmIS!G+T-=H*cxOUbze{H_`sB+vNBwxspq6P?tmNz8>REs;7I@0j^2fQN6%u&QHa zY=G+?Rm8jfZ`kzI-rTB>03ijL}9g~f`jC61{Gndp?8&+OKb4+?Ir#A*rx)nbWx)xRn~fCg(<88m%E0GsQ;Fd&Dlvg$W@{jC1M?_wZeRbR} zMvEP}gR1eyr?c}vyi|lDrPx6~p&7W)3_I(UR{D_Z4sxk#Yyft!=S<5ED&CT`QQ*l+ zn`o;}2o1fbyX4DZ)JyHh<^D>j9FRMMpjtqU==Yz#tWS+CZTLM11pj5$p&}Zd zuR!fYF4cZlIFnvRdXIso^dG>J#We_G2am|5{v~p$xg!FZwDjOdW3-CMxw0N@_@TMc zuCIskJum`)8&TIMyo|TQbYnqhACB)}1nyg$Wl`OMw-RqS+ZSrZwP4S|ua)){cHzSu z18)#!zF4(ei}R>puAiP>U-5S_0_W~U)^bQ`o|c}Z#}D-6F#Dhnn0;6ZqX{`BJb*2p z4}7}5Y-rV4f=+~e{}`m2TrQ2^da~EK)kG04&+@|mw%|WLwB52j^jHR zp?K%SF~*0NFTPnH?&)Z)C>Vzoha>M*MKl^&jjuPd^E{$*0DBhg{_JT6+t*?*r!CRs z`nR3Fm%PZ1e`tS~y<6f#aXx!(hJ(5FxEI^_e20ejV-YgCY7RaiybIs{sIHQI#R!~Z z74?aE?RfUZUHOMIHFVq-M&Q#u2&ta4yMFoI=cJ}J!a26D5JAFm{i+3Y1Z6ip3r&62B?m{o12Xt?MlE%}@}_t?rB7Zq!O z5vu*Txh6ZGnynjO98yi`19LJMEiC7pZ2WSr?!3sd3Jh~SSPG*>4)TYu?ADzg{8j%V z3Ibbwj3y*oy)SH6^PW5lgN@!%GE$rLYwhJ71bS)w>iaZCv=f z562cj?jIfgaBdcB;L<4v4G|}1jTn)GVXco5s!sfrScv+#wdJW(>M?l|mve)uCT1yA zM65VnY`ZvJY)8e)Ozx14?Hg@kw2Jt-Uu%6v*PrO_GcgP^H!_$0WNdU67N?3|L*3=! zP#QORC6k$Tuzi@h!DvGAu5#fmQV5SpFRFOqSQ|jJq{X{4TisIes46_?!0de9{rnW` z4=jbzg5^9~n&)=)5U0bmD9l?1zGgx9t0|s7M2!XR z)n~8+5NjooG3lL`|F!%n>vOA)s;>|N>lH!{+|0?p?CiwrxHs1E9o&biuUcb8u!uoRnTZKX>tL&AW$$ zGpr3T0=FdgLB1`>t9JC~6EDOl2&}s>TKFZ2rTC3|A6ehi&Xzrghy{EGEQQg+FUebi zufFw;y&T}GATY;{(S#J(UX)L1|CVics>1OIu@puNzFq8!Ke*D>Xwf==%bn?YTFy4H zzQUSMyeqL+zp&V=zj~{qqJ6N&!7UN;Q0&#uFZSvu4J^QLyI2aN#TOK(Ax89cH`w!b z9BVbK?c|<%&|S8@`ZLa2d-XZKgZog&p#?h7lesGyTLZc(BgbgmpZJ1#tMh63?06n8 z2gUb+x`W`l)!9a|ha2lLQD4%aCa;*wj(=*9i((yx5!j0&J zsx6h7h@~)^kUk!cG_6{3<3_PI%1p!vJg0?cDY)0rr%uNHL|ut-@DpM*Aw>p>-Z zfmBumSP5GnGh@d=ALLguTFJ5CJlD7LORV$s{~H2J!L^lRu@F(7j#eMzOSVx?hrv&U zpH>VRA+VJE22eW)*YK`vC#y#6txJ!HQ)po<*e-p05^*B!x4&DzV>03YLWpO_XlOag z8V6kc>uBNE5tNZ5L{wJ9x8GBc2!R%7o)y@~e!nPADHQ+kUMo2JQ=W7x|8Cn$RuUnk z6#j(@I2%&YsZ>QM zH9lAhp+&vuo<7z$uW|FKvOe(sAG}snggkEvb_r!ge9uApIo#13kFw4rSLQCBulS@G zLIBa|Ul3SIUfX_;#c9|)pTMuSJ%so~n14Hq7f#I=c^rWV%7TD97$L81r^<^@5heax zb64JhGk)c)gqbL>zaapmAmGlwp>2rj({<~c?~k5f)p%L+3aYeF#goa`V@ABHnCfhmI1Av_Zi^e+f_3xH72WY_mqYgL88s)edBECtsREj)lM2+#~!5mHOoPGTEg zO60D^KOfKXhNoxxNYgH!NVpg`buU@-80XD)kd?-KM574cAu1EYm&sqJiM0v<#Nd?zcy(uvk7f{Sc^Nz^}IM=7Vu zf3u>QC(O$;*2LZ=gpf5J^7J*U-Ty$$vFY}x(>I@5=c>uxr9KBVep+!}I6~k)vLa+l zgt&Ftp}#EnlcnLLMuzj$@kw0r?>0?c<6jVP2P5Qlto3Ui&#yGo685UP9W=F+@)LR& z>wH3<{T~Qu7o)|wA3g^xy_*OcJa$~EL)TXA>RnJL`cy~*{$_)#=e)b4^q~u$@2l> zo7-w}FhbT8fK*lld>b2L+>bXbUGi{6e`P->MkpGCUq$*z|2ft;vZBCNHJOPZfPg!o;ouII!e|i*^J-QfKBlg4OBkUtMVSZ! z2;2vj!e~O?)~#sil58PO6u(4P3xJn_>j+f@zJv2zijP9pt#z~dAPySE-UM7rF9Wwk zz9GKaYf6?3OJTI&_#CY`iu4<%)~ez9G&Q=*ih%C{^>8xA`Oh;s4y>__x?zrU

9$UYTArV9(;JwT09k>Q56*1hlKB9()G*P}emQr(G zKV_~cK*)6f?P4j678SqW{dOf2C+#`Z%*b^EbL@X3U|sAq-}@43xqfY3g*?947G+uvJtSNAo7NJ3>7dcLdN892TNhJs2#L%0HjTX zns>$sJbP3G?gL9*TBcx2r5W}W)b_Ah1%sl^F$F6I|;FrplT@+OYGrlwWPLKs+J(OqAgWa zN$xyPEU|AtrTp5eeT^3>T3Ym-GtZryGxtW{e_o#tozH#Fch0P5&di)?k5+Ai|3Cli zDMZMzb6#f0%JKTlN!7ISV|N?ZCi`k++h|AXiXBF0FF)$xujnh?L<)68qr)@zAtHV8uI z3;H-=lf*H<%{Iu15L^5-bNq)Jw1NCDE|ohWb0VZ?*c!Ium!f+2++JqCUpI?=!7mt&50X;a2l^uYGI0^o z{L;EQmclfo^Xt*4Qm&R*?KG|1YN#0!e2Vt_sHAr0(~InWhf7SBByz?`n=BzAdjDMQ z(&fXn=*3|smclfompr{{^LghtMo7!<2Whh+J@vS+4^sHD@!VpK9JLLcui78xj&RoAzMT61HCE|COhY>8Km{#rR6X8Bz|6~W5mAp^Xc)s$)Z#;FKFp%Az|7xM;!yw zlO5h#aK{j?;}ng|>b_w)9nf%`QV&e1r3!44tDPJ(kbZxEg6Kh+7xc{z->+>+o31fP z5BhSjE$z}x-h)LFa<#$@R?&$+j~0Y13GQc16Y}@*dm8IAkCOJ|JP4^nt%qOs0b@W^ zPyK#{gQ5>)pS$L^*I(X&<~j7iTY=Hc-lvudnDw9iY>V4BnO(658qlI| z&g;&unAt2Ls<0MScm_)g^ykF5TmGz6=s3D*#6)G3fR6pI9P1GEwXmF8?pQQc3Fvo8qpK4EJ8|Q9nga}hn}=`X&c5%b@rduS(SQ^ zqmx%mRK^u1AT7r`+UV&SZO3(_-HxZ_1_Uf2iQLHO`zsZ z!^qEGT2tfwab^}hS!h2k@ob=n4oQO!u*V5;r9hr`{Fy z;G;y;3F{-|i(g6^!+w3k{G(zI9juI82cO+uX|?pHhK5_6knH7+jVA5G%+2>3EA|Q# zI444~zKS+d|0mk~zRX)fhqSLDm%SNSJD)GU*RbUyWL;RUcBb1t+Pv9^VwA{L25KwU z3>a7TU%P1b|iDBku`2l5@ zwpNrXPEa7H`D0plWfk@ zk#`(Qw}@MN9db3WYE2|9cCBfft8RwK=*_Ia{d_|kTp z%nMeQbv2zU&gHEUst4e=X@Svkce1%^`tb<7%3uQLL`drA<=FVIe2kdZDWV6x9Qz&3 zJ_(cd+_m~VYdpabc`TfdtC3&4#ri()VpL7C`dkt)N-C!oW!t|EQD{PD?;dHS??^Tu zoUbCj$hLZM>m#eS{;k>BGIK;ap;`!E2b&gulm1vf$o#Z%l*g*ZZ5K;3jtVbBu5jFE zXrHUynczk3g{BH$w9t}U5#;1;;fpq(Fw>U3C0vXiIadhDym?O>w7VkRF>;C+?NSPl zS9N~Wy4EA&`rb-3uVRWIOuFav&bz)H7E(U=M3!mi7PiW;c>jk;kNzf zR-eZ61@KweEtBkYejw^*jxsK-J z=FnjA#iI8qBqiAMEe|q}oaUSa+^fTyime9F!KEB_Y zUc1(p=9Ev?v36W4m-P|5iL#qU(y=9y%&3%^6r{NIVdS512d*vrp6N(uk!u$4S$pAT zI-OLrjhWfJj7RG>4*8T3zc<9X%RK;Qc>wQjT}u6ncQZ5p`Ag{Fz6g`Ph$OH+Zg=}- z&?C9U%$|2*JaoYPkZZdfJ=`zZxsGPUS1>Of)I{sT%#ogqBvc&-pJmX-g_@e@ZdMkA zEHBiS`#ubOAC<_ywT^o4t!2&|9xeze1%%Y6605`i(w_b^$=pA_v6u(YiWzr$Fd(XS zS;NRDEm&HQ3RH~twwtmDsaw1>4gYMax#q(6$`?#PI%H)A3qBgiXViD2D$$AoDW*@_ z*DY{fQi?nz%pT&@(Xkiz$O?6+L?;HO2v1*1L0&Qq1kQ<&tq-fxO5Z6Jx}wmI?1GQF-pyqeET;PM3+gaydK|=$hM>Sz%3(d@r!^tSetko<=JJChV>(VNB_&EeKh$y zUH|FblCsZ*mkRaZBT<8~tIm(j%@5Mc&tvo&i+}gsv-zL<8koABZC4*Ah)FCNmjp7#?3^mF$1{|Ft>|8Q!g61!GJ&^~Lu_50r4 z1Oa_3SA9vVM29yf(|rr->G7i)3PP40N(Fly*a@q|w8MSr_DlZyw!~I~kWxTMeJZie zewg0M?5n5m*hoPNd{I~pT%IgHLxkV+caU8cAEj+C4%9yxKAE~pNg4<~Yc*^ANNRVO z{_*Q@{ZZf+4Zd(YsM$X_B0OYn)ikg^I445v_MEFHmv-E>@zN;X=uL^H7N#}rFpk6hIeadeJR*K53)XoN9*!XkZK@Vr;I z$*}aToxxY<%73OB{tuH)?`o-v7mlSc4W1bxZ(rYTthFTxudnYrHg<7NZE=z&&t$;s zlW9UaR4A|A%h_)H;hUs*uiz(2DM-tlEFBL{1)8?S(ZUPIQZgNUcYt;N#X*X25fy^LU_ z!zSbFEu%e7qofq33HhH9)!2s(XB#PL<3&B>egNl-&$amJ`ScE1X9Kz#YgVYc38=@S z@%J2&^Fzhym&}R#yJzi2#ka^dqBliT=X+NGTw|Zv*?N5^FD(qb(PdH2aV3E(j?F1h-dWSELff z`{rtW=QYu^Qr7+hMjGrhpmkfH$&E-GQ(vqSa<@cCN?@**)T}c5DPWq3cPT&&d3ir` zdxk~GoCvve?w+Q-Ty5*#YMPiIQp#ONKGFK!`Lz0?_sl~B&I^0RttEpqeW-`@eN{iP z_~wski&aC+$lta~yDPkKASA64VS~cy%7#M~SWY0ovjmH(dSoFFTGO}s zPBfQk6)66K3023rrJd=^O?;%6Xh`uFOh6huGRwCA@n>fkzH2HO`5j?*?4e%Kh5WoIdX@K}abe_)5*d z15k+*r}sMMZjLqSkT*^H&{QOOvFRpENPGOs?PNamsBjR%B7_-GM0ZM;hTB#Emz3Cs;J!pXGXql^6hT0|P z3$Jhc#Wk#%_aTw?DVfgO>fKdOw4lPtW@f}JG1p);z#eB=6{3lKO|dUTpTo`)PQM7* zck8iM>w2Ajm&J|I zt5Zb2#Wxl;kzwGk#oTsYbGg>?07C}2`o4!Nzg&$0pBT26y(-``-=M&-Jb= z2=GNg2iOum`UI^Ksrx=PvS%loBfQURpQWu3^@yB#-iFU%)q3Q`q#Cu4CY#?cU8i|( zTWzhc_g2|3trB!AAvrDI}V*7oJStG5JRQUzg zK}^W=QbLTsf6xMQud#~*QasjLNdPT%6EeX!Cd<3?Y-8&F@nWsL>|Kf3d)5;r!5&$@ zx0LmM?}&HLBpbaxwr&BWPX+m6I-e+!92c?jos~w{Cu4;VC-cPwq^18zNZz=5+N&}v zjXP|thleb6s8;lG#{{kZm}En%u9gZ*VSR+W@vM{4yz^M|qd!L*k(HvYel9bEm8#xf zq!U^tGS!F6T-(dIGi;oh4V_Kh|-)J!$Lnbbf?!TAoZlS))s(!?mf zB+(4ZSZUyVF|85}HE(+Sw*kiTmENgbkx*z6eqz>zjzI}oZ zJ+L|5_|0pyAf)%|PRN`HnNQ2ojmy6@dc`IxdmMK{=0r%*qJy>ZWkws@oi|u=Bw_;h zKOsr&3eo;;y^O1yrifC>@?ruk5%*rjsX9MHe)zW*yZIN^Vc}F|Mqw#T6VhqR25t4( z@<#BKsbcKPd53*pl{k3lp4Q~etr~gXx&@FY|4tpQTZf``o7$2p)#v-DBb?acwN)$Q zB&6pJBV0;hnve>MZfdLdw_xuDd3xc}8UWqz$my)w!$C)f6*sjZOIxr3oWNfoEj@Bv zC%zxN-HGm|b=jC{lXcJz{&{fdJKDh}$F)bB4zZ-XGuqTj$F;NrN7?rCXEc6)zM(VS z{kS2!KGGtf-Q@|rq*WpzeklFqcrjyV*$F}i^q@SImo)aA3E5rh1G?_bSFF}Zi;z+{ zUzNy-3Zw15sA=pvIZ?+__v;_iTK;^R*`J?wyZ_L)&an9pT5R;HlB~xLJEBcbJI|7$ zPbpHECS>|ze|BN;9HVlz@d|;ZaNGg31|jzjhw%9^RmWcx!aA9Bz?m!|i~R4{N`F}1 z$ZU}!&n(3kOyK(Q-FBx{Y+sG9jc+C<>Gnd2!dE9B>{lWn)I0jGn&|ACyGxBdapROy zVH&pxKdrUTWM{weH+|>Ds5(%@h1wtA^li*)tpCo~axPJ6E388$-uG(fsP{6~toEw3 z;lxmc5WH z>#Xcv$jpEo)~js~^T2hLz`F@d6B1s&9lH@1Xa4xOl(JXD`tWXvM?l;^%<{6jIp*+N z0H?p31tZRRBOub?`^X3nLT)}d$ZoZ(#-6Qo`R!sPIz42OR*9TOhgh?WbB<8%Q)4Nt zPbGGyGBziDgE2%Ot&BwHUZemWKaASX7X9+JaqQX@x&IJS&b>ha#D^6Rvi=zZnK$2m zICm35%DFcvfY>_r0Q>UPHn!qMirhyDDNL*NXx;T0`!YJtY*y7<$KL&!`h!IOZ*RNS zZEtY&uRUz^cd_QqC8cz{Yrup$Yg;zSVCmK4%q#s%DUnW?P-oPCjtw;e<_tA|`)()2 zF$~$kH7w7m-8{Fm*Q;$3j2m?ant>(HQ7nb`B2e@E{l}FjeIkIC z;Wn*`Td6PsC6qbwTT6Sth?+zMXcH+ugI=?&4Jj(~52~@B8`e_X^$22H|Cu^Q$Y}CW#0-Sg)Yw@_e6= zMnSt+MwK}8K#@|)EdVC4o#$~&Mdz?Hd>tId*FpRR6Y6R(^us)DY{|jqdrN*5J9;=h zg$SxM=Z=b%6V9x_8-#OMxHlxEUer_V`0pdlS!;F(LY`B(6EY`4VoE>N2J_pJU-C8@ z_{_?kkU0_Zyk(cHa{Y%niann$YK}+7A5ViKx~z5|yC98iUodl93}nyM05hdR%1ebtb+7$Ntw)zOZn zFipsMYFCY4k? zG9Vc>s)k6;4+L-bI;t2R{ zijM6ECU8!KOnKf$?1X03a}g0DW&&9ss1x)u?3Q?>Y}qIpcleBLgYOg_x4ToHpjD!1 zR1|%`#!W49<|JX^_#Q_@I^pQ1D>1&BJTK+ZBGZGko101)=~Gg4XB2|)OPsL{BCXau zto0nN%#WAYMSha%jC2xGm{y50JsxPK_olKQTT^tWc0o8xRe+8~>-TFLDr{pucT;4H zmyp8xR2>7CzCmyPl)$3;r0DiZ{u)266$I9&632e^LkY)idOHiLCftrS=L;9!BWtJk|rd+&U6tSl(fcrB_tzg z;N}>=`N{XGG2xVQy(N-Tn1=C1Nc%xg=!Z`dgkK_~hh69GJhDQKP5`01`Yj9`o+;fO`Gp-5~6fV?2e+g%6fwxYb<3AlZO zI5Kx4(-jrwBqHor z3i7tRCHGRv=s$NIP+IE+s5=39K`Xiwpc`5pzKfdMAq7$pSp#wN?gZRTKy*CFscnTL zYj8bel#M6hE+r$dU*8`x#>2f-GG4<|2ShYN)O7)b^DUWsJzyTlcynArm^Tn%uIR8s zzIe3DKEV1s2^ozEQoMa!QJPYpLWus5Ux2{TjUJ<2pdf{3l$>`3mdef%Q4i=_8Gj|m zYk>sl@F*1!@)gAEM+vS6lnUK!2!9@OR>u`4U{@sjMn*lk2s@z8_F?kI9n%ocWZmlj zn+}kYQBSWYU{<4lXU)~-@P!lSM5sDubwcvbN41dJ<~cc25toAs*Ey&f=@scNXvLgkD3GOQ7Xt6#fXbJ4|1-y5;`C+i1Bf6U0GTe0STc4<_EN* zJ0aHA06iL9te)VhKI?ee_=CZzYF=n$pC z^IYcp@1?@|!kkC`+-s~TUi&Z&^B=6Xt5kNL5~YIC4)L2%5*U5%t>8((>;x|r2ViAx1m0-~4;(BX_$hJ2;eYjucvz)COYhqP)15>Ru|gHRGVCvd3>TsZ}S=L9CC zjq$7p%xxGyP!ef53oI3&LI>^-tOH7Aou0doL@b5vyhoqAbl|qaG>kDTUi9B|V2?cC zQWvgvO!Onko~FF+cfS*s=UV)($Vn991eU_@%HV!5pAZ#ro&(@`YJ9$n-^y9?ye{H& z0^e;a_p0d3S|#vH6#PO3>r)A=9ZM;1@SKP!6~QrHn80yast#Os9LtGmg&_FdHh$Cc zTEdPaC2>UKYYBqi4`L}CZLE~aj^iwG2{Ek@1ix{|?=d_GyR**;9wqob+k@bWtp32U zoLCCCf>J6w9vL_$71Ihq@arQih40l>0>53t1kOn%a9d#lze-XG{Eh{`M8UL5;MXpg z_8{!Cb@3>{bHan*imd*?F^PCico6wI(Cw=tg<^lydf<7E3H-)PA?&z6uoR{hg5Y+? zQg}Y91dfxy1fKIMf%^j!c&?}fj$FkA?thiQaj%%bIjIDW{lEmSpGx3ZB~0L`SwYz4 zD8YBa*y3PX)q(G}u@u&=5_tW<1hy+GfvqSeu$52i?YoUbJaj;z4EyW;6%0{5mM>=x(hK?mHd<2Xx9s|2nG9!nksV0I`K?m;Yt z^$8u$e_W$PlnO^DVA@3p9XRR%OJUkY@B|<2R)mNc?Klnu(<55%v|1`0d4jDPrd@<66^<#vQrKd+2%fMj(IPnZ1Jf=-=x}}!ZH1*UP00TO DH1aoE literal 0 HcmV?d00001 diff --git a/kuka_kr16_support/meshes/kr16_2/collision/link_4.stl b/kuka_kr16_support/meshes/kr16_2/collision/link_4.stl new file mode 100644 index 0000000000000000000000000000000000000000..331b126d3f3628c2ee11acf7b52ac697305d06a4 GIT binary patch literal 31484 zcmb`QcX$;=_xOiijg(LXgwUHvla}o41Q6*EK%{&r5kl{Z^dy%eQlv@;CA?HYNpQztLG4 z8+37m__b54{kVn6gCab>6F-Lpy~xjh8e>}QdC`z6IVZc%nfx1G=ocgEe6-jc z5$7#XxD2n_V;*O-@>(eq-nR?A|0QR2zKNINy&EBX=z1_?k*PC`BE6zT9(y*IZ&JTm z#XYTGH`xBNhNQ!Dw^z@7M9lUgR^r|!;-fni1!Hk>GFHsRj=WWanf8U!<9W)E#wz?E zx<6;{b>WP4GM;(2g$)#)rX-sgiOIPaa!|3 zPa+*j3@y~u9z1Wk#S$(Dqge4M3`FO0fmYTNbws^~^`Wjjbt_yL&pkIMlKPRkD*mJc zXI+Ls$z_{gf;PY2(zG(kNql-=Fn^9`>|BQfA@7u(WhQ#YK+aql;WsC$HecUkt`Q!y zT!pi5JZRiYSZpy?b>=A}&%{RNl&upTSwA{fMtZ@a>PBerDj?pToYT77q_`*=)7Fvs zZJM_^58pT%-uUFn=Z7EH>^-8cSZQ#P$KWhV*FmGSwQ6PT*xZZ zxtjRrnyH9sV|ws}nIHPe@X7x2kK9(y>V3ta5r04{ruRfk=4APT89Zp`n=0J=t$94< zo$Qd(%-}2DcmEkGo>ootBXlfDi=~TrC_m|CY+L1(-oR6%Medf1{RkaP5?Ov+#uM7F z0%FrA%$slR1o3^hFh4@alEk*1D`7mg07Cwq&J!s*wlC>N=vcCybeOR}&K0*#W$7Sp zPc1BDT6)}}T2Os#WAZc}^QbCktku5-tafT62=#iR{@TK%sP%8iVwN(3?{^3H7s0u}M zSp^=x7TnW5~2TC(n2ja+gyxXTqr#7AsXxg;S0-fL@ZVO)589O>}av zD`BVAyCqu+(=xYxHZHY1&ze9B=1w zR_N@?h75-ei2@nbu4FMQ6^*fXJsU{~603os2(~X0h=<1?b7$gZdvQpFqf6`QlFyRz z0w))?!oAZ~xX_OeykS>A2cq1fyk?tevG(4T!~6)HLq=qn{qmSUc)ztP=Nm?Hl~JBg zMyEiB$G7d{6rAjB(J&t}maw{`yGGq@6oSGT z)~GTg%ZepOOcA)bry2CDl_ES#`Way(o2qca_g@)djfO%Cj_2&@Ht3;u4xTrzT#pvs z+C>d1U9Vo4z$r0yyqaT#9f%gWIu_y{XeGI-B|NFBdZMNi{yL$ad$!f*j8&gJK-~Fn zto`PuNINVlhr1#VY2*!y8>9MCXzium0u%GP&)>cRGj+*;RDNv5Bxhfao2sQ!IjkSM zH>%RY*j9av_Nxkk%=G*j>D14;&nw?(0;emV>y?PHW!GNt_%o5t*_!!@44gwuGd3iQ znFa4hIs=N%^0HF--25JikH_g!!UIHMAlhf81X}wD%~+2c!$h5XvGx~PnT^vTD;bi_ z*li#_2ckpD3mBcgTwwysW9;LF%zTs@=|nZ0Wz_1GrXijEFa(za5wJQB2I4OurgffW zpj;6Grv$71&0%6b=4;^gBo?@8Fe_{ zOnrI90B_jcBWBLSgVp*`ZBL5f>GlPYAy)~QgSni88LJbJ=&kzmL$h^cxFURS-1S^* zH4&G~^LyUuK(sylnpJIlSy6WMdx|){GlZvn66q(yr~9nP@zk5>1c(2_S>6YCc^w?$^TB)mwE%qigkuMuurwav!mBc0Ox% z92d#!Gs^Jg3d>`xMvX{u@5?3o7HlqNvlo-pY~V3ld%O1baL-_avqni7bhx@>hl#Co zV(nUu0|=4cmq61)y#(fx;$L?aCA-Gj(`zQ#1+w*3GFZezZ)m?^ZusF(-f;2EUF}k% zV2!Huu)jD_U~b%}7cSbNpA1tuNyv7X5I7~q%9#Dd{>ibyyH8vuGIo^iPoiOU& zafdZ$SH{roN(LcNx*?cm?2E?}#qhvHKDNpmX03CR-2B#PXJF#ki*ZoXpwBNZ4lB-# z^|{SI3U-K}xjWJc-B{U><%szzimdur8(^%tH@A5Qh=bn(fph~*)75#;uU*ZgtKCCh z)S5tKuurEed7hy07A1__A^dpnle|UGC}JCUDozejIXvi5tFuqjkNLGJ54^LF7u^u$ zWQ>)(wO>f+j4v|~rT)0Vw_S}0*#w{O#KB+l zC_>w3xEzx3r4+p9koiHISi54a?vAHsg3^S8B1c%EwQj0#%C!C#OC6?WxX_vmWPkeo zA#*(tjcaswaIBOycNO6|8j*qcW?(h(dV^f?1M><8+XF#Q>!>jwbG=ap+aT#!q4;km z#F)e0_*kt`zE#+_8pv|^R#fPSo`_k?&4dP{2|?FzAI;d)f4}8NkL9(4VUU#r(g&H?r>Mk5)Q^j+K#?qoUT%FF9lL56XD)^}^>E*()B(1Gi#(H+W&IcD9?_A5*-VQIkO!aEk=&o1B(zbyN zg9pKK{R|fhU*~h4jB|edC(MsXk447E#jJmuRY%6!U4z;?L`LPjN@s}K-^~i|^_mI? zUFiZNYE`G##2XtyFDc%{DbT5m`{rmX3)7USy7z{ev(Qev?SzgF9-Vj$Vj6n;h5P2V z5wZ5U>KSr{Mr{hpA!E_uuZizA#o8kSnvinf9OBW;*pb=2%pBM`ze?E1USvMlqzL~o(A#ki9?{|s_zdsU)2m8+QZtF)oL3=+} zUIX0*SRSqs#-2?0#(cNbPP@auy@?Dw+fm}*uUDB{`o-D>v(jAQoDiDrjXB8kBn))^ z8iUP*?kUnl1Ol+5yW4IYGmxs}hFZ8%OF2jbesO*aky~nxpPFkIzwLyhGALnhd6)Jw^{ThXOG083` zKm!O#HcDTK7K>u18e!dPxE_{%_l)@y>bw4u9Vduags}!!&lJp{Mgl<=S?!OABK8yydRDi zRzx!QzGy=TtdUbK+}B2=PW?0;j}S|4kQ-yEmgn)eoD7;5Rsjw63mZxoErv#BOmg1i!&` zg;Qdz&&^+q*fY^0yxk!q{MP_g+L$^eIobtM>y@ts`>goUIGYqL)`s6F1eS+AVT`pu z|DjkA7Hc1Az1GHFF6>*1$unH760F&e(l7d~zqkiB=Q{hMjo)A^m0FO!ws#fnyT#ff zFo_V@mc=w<p7ZG&Bb|V3U9Hf&FI1g)77QaEPg=Xd>!0&QK&1TDMb)luXH4T>$(Z$b50SOP zPJ7bucpIlhdL@z#b@ix+;6P0IFy6-LVuH#@crBHm0{`xr?Ed~;u${oa>+Zg4eGYnJ zzEobbW|Y&v#y+L#=~%MWv`;r}JX-F4?U4Mbyc!TzeSbpN0;U;zb5Ak;plLocc2p$s zc*%6NZ&8N9W(bj%1$bC?h48hbPV#v@qLjX?-(cGSdm|aE7(S36eKVME?3iwUsI+9d z+Jd0;qc@irYZFXye{(g+Rk|$;(vc-}vXSy-vOeI;WbrkZ7;}KgwM7!XSjfiZj1XTW zj|eHTH&Q(4oZG~2WUhR^P%L|W>WGkPKooqR5?BVMpWHudj!ZVikiFSNc##TfRZA!* zIG%&)EV{PLY$IpiXmPC5Odfh=qS{f2>C}?W&S>|Yv147<8n+fli}i1JCq&HBuM{2B zped!__DH&DcYt@d!?U_yi*bN!dBVmm@J_K6rL=4~z< zSHI{4Lg3XI)1WheU-Ye9OZK(hQq07jG@L`4tIEYA#qf54!6|3nATltG-Gy8%U;#v|<|9_b=#9`k7#kq!EZ z!Q~TqzmvZbuQT=`*Q(k_$qv1I32Il?)jv>I8{e2{qB=29-VIc8gE85HKR^qvn?8gP zs0~6e%~;K8r;L@LA%||5;?){*Lc~3q_lR1q&KP|Ia<%{8wMHHogXN3;pA~a_hPw~g zs=0+muq9^(pO5UvJnM{#Ks5NfyX6`8wIWj9YD{QKRNQsMm~%E-JgN4BSI-}wIweWE zNS_0}r1G)P>WS5EW2&A?B6xM1KBMyrg4b4YWw zA?KIgUB#}LpIzyvYS(vy#+P?l3t&MSt_Ar`*?isxefOB{>Wol?_IcA-KAN#xzr>kG z_nKn(!vJT;&DY(TA+a6lF|^J5$H$pTdrVROd4Pla6{c|?W9kfzkU8d z2m8ga&pP4#o9-UcH{j)F3HMK%uL1Gh7Xuyq1{2ipvuUCsZVdh_?o3DxCnoM)<<0gy zuVi7pooeBImIjL(({hJAd$*>8{ok0T#OhO7%r+Zi?8m>26le#FOZ`)OZjpC~Gq!no z7PCcgjQz&bk;K1?Y3^6$v3@X%94};e1KZpZvE*59}MS^;QJzhFfxH9mkTi z&)@!^M(6mTtN~6~(@untv9!+`)3DZp{Sme)(wTI0ma5T8E0(8_c zU83GvNx(T`DZv@x-#-%7x+n94BbJ#7{l=&f720vRfqjwlh3yYagEjGYcTpRNQya27I2KNq z617IHHA*ar7Q^m!<66^aHQXIV-3HiJ2Q56uNV7{%Q#5NEB!ag6pmd+`$N?P3LY4)r zgA;m>G^_MB#r7tY!16H7*a_IjDFeGQMV1c|XfK8165YmZ$vDtx3*j^AGUQs@L3ku=_?sjtRXQpw@)G`^Dhrd;_c>V-IxU$a`ks6+qH@ zU15w@y2MY;AL9&fGD%tV>6W{1Z&R(caN5|C_W~H}xb`|x)x9Um7Le0~yi|#BW|ofR6)K=d_)l;6{0E(gwc0A}`7ztj=gZ%EoVSd*GD7K8L!h z4t2Hp&@AF%!8G=xFot%pEF24aSSTUSstt9|su52S&J|9Hv02a_EupUJ=RZnhq}LnN z52|&jt2rxriG#3y{7~|-&3=?SBjb6f$YEj64W26*>sI46QECwp7EA}# zZLU&^sa*or!70rOiq@$xCw>KYa*zx{6Q4}{KW~a3cW^O$$!9iNy}USA=)^a)Alic@ z1lm_4;}P~h9t{$|LCKH&e2Dn3hz#G^bCB`6IYQhnp2*K`-%e!UaYsiKTAj%l#ATxW zDmKl3_0O6qUbN%tWvG6r2Jqv11;sF^-I>dG+JrzgjcLYy?pajaSi?o@KQ<5ommIef zoQIp2Q+)Q9DW;DHK5HZ$NBsLkS!U%VTWehR=;5y`#mz8?%&_s(pH)EgC9+S@_Df z8N4|0+dem-t!#ce&=du(R&;R5Ne&4ScBr~ps){KV-2noZ7S#{QA*&rw#jFl8 zYFx=cp!Pu864dU|u*zajlSDqp3?;q{Y)$IjnwW9|i2J8YiZ|;d^YibwbnqKYP;XR) z2WQQ`u=A6BZ#D;eYcWlIWE;azm`iOg9$n8xWZ-lu(Z25rGig5f6Q>n-Qcmx3eaLf6 z;v>VpGZ<0rSC|v#nquwel)$mH&M3Xna2s&+F5}$JXmPlCZPMGZw+_o@Z26E~#$h0) z_67pw3a5*EKHSZyd(RmvRsS&*zwCY;2cSqIC5{-ugiaLf~A{ znYzo9Ffp%PGA}Z`AR$OBy!x&@wW?qi2 z6H@4>Uc`rtM--J2{B=$-q+&APS+FaSfoBFh6M?@Z@L#j;phVv1a8E*D8JK45YS?k^ zon6e?v8j#nm%y!GOWp_87NqnJ$@cL1ea=?7%D2|d?u?7*MhF>8ds{FKH;WV3@i%7f zvl_k`r3kpY;FY(OC876?sE1{Lk01EATN>Im7EMru_QOa*)0F7CYnPD-GhB!6wR!lW zLu%fQY1fFOIZ^dWZQV0gc+DkU8+`IzYOr)zDg!bL-1V4kdrK?y4 zcd+tRNFp-O`849!fHN!)dx!`)Qxq2wZ{nO_8Q2p7dgAS~d}YjNXZoqnO?~z>;c-sY z`_erg$P>a?*zBWx_p=dB#bulQ2z?G+_R4gcjhwv7ED2|wd*taWaF4_C^a|&>54T^~ zw&V@wf%75pyK{ad(3;9IO$oHt5(4*pOv5(^KqG5XE16H|+)|){>p56hH{1Q;`u2H%5A&FgJom*5O7jLf~{U%~&q>lz#^vud5plaCEwjc)YMD z3`SH>LsWt@ceC~f3QXWwcs#;AVK{Tw49?u0oLY_$B$n^SI+R@7oaeT0H<4{=;C_s( zN$9%)Px_0?a5A%J(nZ>LeK!LQ+>c#P(UzOaQ$%FozKi97o_O(JUbi>wE|p)*6GlE( z-a)qHGg4QyxBqnEU!E6;8TBZE=PvAFgL!vnCGk3(#$7X_h#lIvjj}D--F9B=FQK+` z1vtN31Bl{LMQm*MW113myIwFl!f9Oop9AqE7Mk0!Jh*?}<$}=(h@d@`!1D0Qz}UqD z=Zum!qD9Nki+F=NHFHm%{P2Yr`!6UlG z8^1w4gUDm-6x_V;0L0hpdlFv;rm;NuKEt~u#N?}{sI+2%z2ilQyKB+PCg~Cn0z1~E zga`-X#M%YK&wy!4G?;P5X!0AZ&O=*!aV%UvxZc42_{=44O{4_&gkT!ZehjTCj)f-k zu~Qoo3sTPv(rOG^RA2e8g67n)7`s%ZvFOt(nO{0z(ZO%9zKgYG#@_qBkvP;Mkta=h zn-Dk_-t%N^QDj!J<4Z0s6-}|R4D9{D@)(;t`GNW9rYW{wx|83Df4wk*o)$spBq;H1^Iy#8!xH&}W^j)sZI4Ce3K2Mma0{Z^ zNV7ETvFvFc8+2VZPbJ6yLWGA~LWy0;j~-p`ydhCUr~^u`S5Kb%F^h zV@duhW()9sRJl@7Ab$xt398Q&g~QjH$iAA1>^_cXQM7{vtHD?}5r4ux5ic--R~$^k zS8jagO9bk#9Gwv1mTu&aNeX=8z75!!c45L$3F+=<%eQ-@u>q{0CM*EH2KyyGA6x9U!EuCJp6j)iqQ_^L{BB@qg@Al{kzmcU~I%fPZh zZ@*DVJPF!q|2`fFlq-@h=_UG$4%07OG_kIRH9)j$4ZQ??HNwPiuoi|>Vr@|>Eawx0{Oz}oap=V z0>_pG+|=`ZJ3$~XIklIu9gV-wKnQ$R4ezBhRvNy9kmE{t$c~;-0-Y))cae!~R&sQ1 z^Co-)qV9K*tAX&H*`;+wZdwc+osS=a)3{e>R3`+Mr_YPZFWxYgb8kC7Eaf!c+ANCR zO7VSRgXR#QDki;zv^mNx*()Ns!UV0WQ?UQBQY7+4W+=Ipg4ZjgSwcDF>Cb=M)1PEL zC$Y%vBfp*ShWqUVfn(t{3eSAxTpwAZFpYBvnx)TsE|AZgXckysfiEtC_q^Oa(FB{-PP2 z_d%zSaLJLc7i64&FU34rBAM4(7$L|TpWdEfE|EJw^%B(15Apkun)YerAY&?6UT1hR zkDl6)^j+LbwCxi*rv?!1z>a#-ERiQqdRyQ(n85ANShFb)%)ncwSaR`>scji~TNcyE zDgqhEDl%~_Ol#ZF^+w5)XN}#HX9De|7`VUUHPPM2dFt-t5CZpnOp~)}09+iQ< z>15(qn8x}8e0MPI`wSPVw-;zXf@7T#_fYU<_`Wki`Y!I3I3==ULUd}ZS)$zxXb-fH zBk&t6gZ6g0|1sFz{~*3TtbgK^$o>bBfeA7SSZ~-XstWr!O_O>M0+$x&(A~#5?e60c z0;h{>8Z3I>UJ)U1EG&;PdEX$Pd*6VJT6BAWv?gQq9-cPy15xpdfda?ExxypZ{r1ip z_uD%HTM#%`I3+m0yZ4aU4~UgDyAv5CT{0)iJ;)$;50b1=WPJF}6hSW;P_?mmr)4s4 ze7>SUei1Ux>CC|3M9Kv?k-|SZZel{85RqqV@tIq&2N&cN_kox+ni4n`ol7o&7v~Uo zajq3fA#(|qM+tcf>6&{A$wa;|1CLbX#RE-W-n$#>-n%0N9`l%ny$RoGDie9n3@nez z2m)W91D?CKs}`8ZlST>jjZU)fOjc){E3^j4jf)k z;5WE-agTwzg0pH5S8~zMbAYrtrg8hjiUX&qy2ELz{wsHy_^TQumTzwx$`R3`pvVKn z!^JyIoGz|6oRWL~>N=diYW2qkLg12PTAq9aeKa*%Z2CCPEAMvceMjjp(Wj8)a~*y) z@iN*a8V-Q(h3}`|3&-+g*mu8LGA|>rzZKK2j6b?WiJL2Lsjsi;TU0pjxJ;Q7IF=0S zlw2Y(`#7hm9Z60VOBs4+Oon}Dge8Ls97~6#3`%5MKfxLBe_^&vOMhu5Ehp-GukyLR z3!-x6(S(eZ8KIxMWJc&%Qicw@ zxtf(Y$q9rnjLSDTT|J7hyvzwnV?u`&;d%e^Xy;1%#kP#4zXB!G)uTv;^>cp$$I@Y( zlAEjg1&2A`7>R0}>+fpeSbj2CX2i>AR|d@Oj-1yiLx_I`{&od_^jR_rgiCnWAneXhMsODWgze+-fWjTCbR+S7U z^czgbuzv2!m|Z@OC*F%vGW5N6oUSDFb4uW}a4bx_1k{x+>q@?X5~^=XN*p>3EojL$mubl-vTbp?lF-ln37r;B*Pnnj%0_FHy7en#;d1D(D{E(LU?{$*TtFph~5CjGGtia3{^4+q0_~L%oQP6zXq+G9?#q_#OiyZIF_G`Oo^A# zaB{h6b#d}NIL`oo>33J)CQ^DB?y=CjGMN!L77D{nB>DF=wT^SSa0AtMb*p7;LEla9 zjD&uJ2^rSUl?e7=L0M}b~d5r zM14BN$vicP`s+D;c`?Ng0^X&)r;M0>{E(LUR`&jxf zBB-p?^(l6j_+dhfz1a8dXthR389J6E^y=eJ;8-|J3D6lVtuyHJ z%~FOw9W7<(u#(}?gnWYu9nMI2;QK4?pG+6@9d)l=hV|?t!+6wYPJor7expbdV3(x* z0vPPFNf{m~MZN*OR{dg`3}boN&ycwctv^Uwrl>W`%n6w1)vuRH0#~wFk^( z>MQs%7R+$!m%3g}Xz4N*j3V{BA~Fnfe%ddFppvUxL93~+2+CMEhdL$yazJU*e;W>J zLH%CUt8=C6UB<${=jA8EBc;h$THBUk`3(A!@>2N`@}(m58%e;tt9~I(hGBk8`|UGS zaz8?^8Ir*IReHZtbp_*2{eql~h5N3SE%TC2_{&HecajD#h5ALlR}*+VVt-<~43#UL zmP{A7&Ht7wnFC}eqz_ND`nvE@xRH?o)Af6e@S{d{OU^k03?Ae;mir#uV7|K z`z^YR<mJ=?2qfCZhN~reGV@<|_*;)M_Po{(_xvmo#OIt6m zCO|JyzYQp3;oknzT=~^5o=bE}q$jF!=owkc!0X5VCIin5|J(WjnuYq7nv|z~q$F3W z9JtkBq^e)Ucy(QA{X@pm+RLj6T|yZP&+Xc`=$|X?*^&hAyE-L*LicJ(V2{pA3Dq8; zi>Tj^k_4XHUrPA3Iqr#i9`nzYPD{$bJyBa^uO_rtMbdf(e>I`oSrQ;y{f_3V3Ebv- zeS9^6*IHeN{)BE@nG-x;=^F7T^czXw7Swa)s|l^WNLu$Ee*$aw*qYF?(+Q6Z;aZeo z+#Y^}1T>MZS;}X6t;O0aop<$`DrMkN`%)RI?`r>!B(R?NQo=7+TJx5)PD$pJ=1Qj} zV`+O(hV|O+Pw16i#=@GVPRXCp+O{OH9i2I$-$(+tptdaiWne0C)dhchQ|EG&<){|CYIR51Vm literal 0 HcmV?d00001 diff --git a/kuka_kr16_support/meshes/kr16_2/collision/link_5.stl b/kuka_kr16_support/meshes/kr16_2/collision/link_5.stl new file mode 100644 index 0000000000000000000000000000000000000000..029bea56982f24759279b509be318e1fa9afb922 GIT binary patch literal 15284 zcmb`OeV9$v_rTYr3B6Aeeo|vbB=RyvGWVQ)$4eo3Ns?+ZzM_UnNQQ^WjUh=SA`yy6 z@{%H&d(OR+*HoeisSx!|QId%Y{npy&tYhsv#`F8*H_ub;=kER4YwfqS)?WK`U&}jF z|3Cj4B>~*Lb*%M@RS-)*n(S76YmT))CF(?W&y7Zw4Yw+djysX7tmuH+HFY_@XiXGg z+9fOB|K*PS*wN92cI1bmB5D=Cswfm0*UM_taJ7^3Zgne?)hXJj!xAU*L!Jfje)eXk zbDR7ad^gyJi_)V+gg<*HWY7k2{l`n)GqVS%Pa7|95?=Uo^yc2Xt#FrQ>uCM}C$GX< z3oacUdU0SEr}*woR?eXEDC3KE8|`Z*9e1jKk*lh<`qw&`_ij<@omtjf%YU*8F`|3@!4`>PFCvX!Kv%H`IRk4<)9$si{cqo*_AUYN)pp@x zC&x|2aTKc(t5@of*u)71cCbrYy%CbFBn`0BsjU8af0?^CEu>^CInz=$K>yTib>SI^ z(G2YR=cKi9(%Vj?PR&qI?s{F6Roz`QME zttq(M8~&bb%NpM8@RJJ3@d503X|4U#v^;fUSjA?IE}dYtO#RTBd!m{3)~V^%KaEye zksoidj&25vcIe#Kl5wtDec92zZB4d1u>X)P38Pj0CqqQ+`!XGgIup}WyCpZO_D^rI zWxsl^I=8iW?@sMr&WbdjgX8Fv-NfG1e}YxF+i8b^yeZwGo*}Xq*SvLMq074+ z8s|B@{&4z#9JW66J3zUt5^E;z-A~397#8m6A34@7_e7oe?I)u@J-5ZW>Cj3iy!B1A za1DK%*aU5&Y!&Pbw2#5=(Kd0;>x-IRac6$)+fjwCtdUyDo&cU7yu|MP{7Y`*LA_(I zT(i(R+G~N6lhoRgvtW+A)q<_o-zhy}X&;ujvPRC8>i8e zC(vFsL*kD&O+wBz+ZAtiA4K8~B;tvLe;)OE__oU|r~#S(bBZ)+ZLcQO$~6-$45-I@{8Bp*Qfo+PJ+{n@U2qGQC=@?YC-s zxT;ALMKv@+@^_LpiOR1OyBnWOacei~tN0v{7v^z9R&}*_9PnF5JcE&bo1F&eox6QI z*fwgUr#3v!vFXKbSCo-KGH%L?vWJv1q-=n`qcUQv`lh>c4rC~v-N?`ih9;5*X#C}^ zv3?&;FM1nCE(zI6&IrJn{&}$prw$fXXuHmqglxsTgyIK)u?1VLM%VO+oqDIl=JOF> z+1ldWNAt!f&GYB)eZR!s^6-o9n3cVitl?8jmRj}%@O7xfnt;}4$M^!9EkNXrzYH(K zXOJQ%To310ZA*5JDl~kQq)lQ2dbQ`#tEC-FHe>{r2z_5*yU=R`RPMXkv2o3pelytR zHK$$8tEMd~dr@uSo*T5;>5fFh-GkjAZlfB1mqh-vI4XP6mKy#>OFecpT58c3>rR#- z&``@bFyq0M6j}aCgummoCeoIOo&XM%%XEj`l^?6oFVmHpgh$TQQ6^m1GC?cn&W-j9 zBmcB!Z_ZVIJeW!Gp!BuUivqO&qNDvWp7S*a4%y+?t6Su2S4Uf@ERr{cE zQ9P@Ksk=dBWEHzda%;HuhTIt2E9y(`SGFs0wDSPlRI&T$<2Br#35490k_PBDWvx4T z)smtIUe1fn{WVEj>hS0HJK=#(M73X9|CA$T1H6XB;nhou+9M%rq$aW_fN^LO>0EVg z+9bvvApBM}hg#9DBzYz=a9m3_6Zh3k;|{x$Ag%O1My(_b&sD@|3yKVpQ(pvWv?%jbe=P8~O>X-L1-Irxg07K{J z#@@NChMRPv*znFAg@vn*2?aA!=}GiawJ_?t0i(W7ZPwXFD?b9H_<{G8=g+S|852@! zxQ$O1+dMz}mS14;>=I$hn1pdj%H!$oeF<@iqgXM1H5`sraJ`JeC=bI#yE_AMRW%674DK8ByR7Q zX~b|+L-vo9dBH5s(T(=x4JFpBMY%EZgB^bOIWu+BH4a(SOIBVOimy?gMa6rfXWJh} zZ!lopFV4&Thbi_3IR$rlp3~2;uxIe{CGE0$+bL^mxdW~qVi4>NDAr>CL6H+c)AFtD zp3SdyAFn%9$-dYdP(&tW1N5$NhkbFprhEE8zLKpB8NTl#Z80-pRZ%xIT<)IO)?7yb zyYu>JjnXze6_##>7lbAM%9(%LZ&gN&_Ga0RP zt0}KnaUgkJX5gJMuVLmg>fMvA7JvJ3<>l&QRgdmOik}Eo^(+?bT zS6#WtrdCBaAB~1b$3h$pK;Ac624)Q$FKYnzbx{kNpLEy!I7Jg&BMGS?K+noG)%b_w z?&SIn)QwjhvNmm7>clVqUiZthV2=E@gALT;-#>BJFT1uB(arfF8mafEK?D3dGeh;A z{<(WBql%K6(3qHzvN1x&*k=pIK6b&_rcz%?2eD7)LY%AK;X=CviFVJ#ZZp?#CC#`CfJ(t~z( z*M@fLUpbn878r$T0MKv<~~-+>EVV}z6_ls zlMy+<$vQWv?s=)|mu-9beCT|e9Ib!SLUhsqvPM@?UtRg0{rRE5GK9!7Bob&P^sEDn zKb@+QYVEdf`LZ_K5=~IQot+OtbUq{vP`5?8I<&ok`lHt>t<_C~FSX#!p&^+`Bl>K1 z@VOpos!#NG)o1lMgP>MuODwV_k_PyodsVf4V|z8e;%v4)7TGHzFyCrq@x094mhIQ6 zNzs<->lGPV2KP$@T02dfGVV=JS9|*0s{UFv$E8-01{JJGjfqiiMcG06y;AKfEwJvz zz5DX9RJCiDtt!3xA5E-@RkmP5g{W*LY0O{ksiYp+*GaYN@|AAIx)br!0nGY0$}2L7 z)BjXgy?eD$Bc>*48Qh8pmS++p#$>BD3Sz6Kk7gMIt_Qp zj8 z!Mhq~BdA|_Ka=-1%uGbn)Fn_?y}svDZGHYe{!b{rX;~>t%@!Qvk`-y{w@+?Vy%&6D z62dZ=wq(&a*Q%W7H`uqfX%zE!b%=H~m6O_y35EMy?Css){&BEEEmiBrM;+fF2xl1N|e5LxSaJGHn(w3Uweo2OUH7f+0Qxas%diIo^RMOMV&h4fN zZsngSeM2&3gg!cGf1J_KE&eo!mh}6wZYAEGF>;D}@zpDbE2w8Xj&pmp4I(mq{~#IM zO40z&oOwVE-FecjQ~x%bTJe2=$`}ne6b%I4K;I2^Jbs@V^Y;mNYWHU}!L5kksNW|sryi@L8uqwCHE4PP z&y{XP1kR|ACV5|Z#1p^WuSQKh={BhJkUmj()*OnKh~Q`-SV4?90NUN%MP>9j>DJvd z#UNxWUJvq#00XOaQFB(DaQmiCGYHv=ipeBYHf>4 zw2WQ32SSk-w&?X>OT;Va$*AGfRxjjB#JKTpe9c_;=Ve{VM5Ql zoKc^Sl5Bw4(_5=?L%(-d>^h_gUIW=m(g5`yIc@h{+0%9F2No_G*g-!|Ae!R`fMNHh zsCw3HcSu*yilR-_1hwMTG-vnUVH@qwR{S1)X+b|dS3ILcJpELSB50pDyYC&}Xr~-G z>iilFvQb4M8x=$~Oapv)V1u1kai??q!M<7s*U(AjIEcz;BbhU()h8={554GXg+wN4 zLRztgKH*0)q*dyXqt+4B%I{Z4GXDH%Z{Uwf_Y`Pl39WRE>{s@L-!0`N+bgzVY=wXP z6$*WG733Dgw^;ObibuTb6S7rM#uq;B$s>ji$kY92wOeO%yu)8m@ryD?GG2bSEJEg6 z&5SVVzx};zRUSVz;kaGDfcq~E6mf7oM`dac5hi5BB4Z!f6Tp@!Ywaxj7Kc#2HPAOV z99hV3ap=AS@F^1E1VY|~h+x{g70ukyO6%74{gFB|!TAf)UC$NiZsam%`9vEe>32G0pCUVjSXP_*%d5B z&>HAhM1SPEtkwFc^ATtC9ZwrCaZ(14+6yEl(T93-Mf-%cmwnw0j*_7Le`v<(D@S5pLdGPM+aYZ(6^PwdsJD3 z{N96o6nQ(Z{W)cb?~s}Byqc83(&;OdKr8&FL~2{Mj6f^;ikZJJ(cg~-|ey{DC1}YTAxAE%8vkI?CB{ZC_RJpcHSt?MaWhhOHfY$_Z1}T z=&pEcff4CTi%R9dGeFle2tS7N?gNSbBZ7NZ$0aOXXKTb4J2Hdhje`kU!)5x`-RQ|j zJQ>_dXSRe4850>YB64;m&4d>%d5kB6Ybd_rGPRPlAp?vWUn^Pz9*4Ic74aL$q&Wlh zTuDND11@{7`WGW{fltU9rfIIY?B)8p;FmR|+XEQ+v47=^7w6$PTJpYtNF=CLA|ZR? zk<))8M%2eUk?67sS;JnR2;TWr_GI`mgYilx3E7iJ%<^IeW8_ADFCpsl)|*(m%kZl% zl{t%J-f?)}GQpV}YDK?sMu+cL^qVPzYlz^C7nS)f{rm*q^jIF<)k_mHN5-%3M6m4A zgnX6Z49ocm`R2v1a_1*lIU zg8VWxL?Wb`_kMn<%A$L3bmC`b}FOnf`BA>ML6I9Ed zleIlRAy<%X<@pI|ug>Q5&*z;vPfcUu)jYopBy?_C?wIov(k60l*&y^TVedu#O09U- n4MOh{9-&VJT9r+34H2vfmCxqF6X%L+s1?#Wv+bAtjPU;gBA|a! literal 0 HcmV?d00001 diff --git a/kuka_kr16_support/meshes/kr16_2/collision/link_6.stl b/kuka_kr16_support/meshes/kr16_2/collision/link_6.stl new file mode 100644 index 0000000000000000000000000000000000000000..ad2ff9f757e23d1dcb036c837ba11babe6725ab1 GIT binary patch literal 15484 zcmb`Of3RIub;oy*-(VUm*b)LS@g>UnWNWnfp=t3&FFzi+h5ryackEY&{NI1H-#>rc)eUHE{&HW#oiuemwCeZANzZtnd9Mo`bznhzW z_PKAi-V=Y&qprU@X6@+kB}Zy6%zEL-bkk2JH&D~i_t%WNE8i6xQ|1i$zkcSp*1_+c zt~MP0-ZMc7(q-b7rHf_%zDqtSDILd&^}XAk+)PudvYwY*G#e&UlCM9H%|O0;t$V&lYF z{~BMm?>p^o8?2YTJNVKIsdJwhZ2DDiUDy8XFAvprh$ks}5w!Glik=2>;JkCw;jbPd z?RYqhN1NjzV~}DDx(U|g+%%bqH!R-2ee~+7+Pmy`)N99Mc)`Rp*>AUu$Hkv-`u|>e zVtf5bM<~G(OO(C(mpg|1MFYd_x;IY5K!IG}b=TzpJxd`X^21g)x`e zmtyvTXg#|=bsHWOujW2EEj?X7)9!fHWgk2tqmY^=KM$L*1)4yq8;LOVKr zb++_X`-q9zaR05kK5lyX_i6GMOSz&_tZfjo{##i8&fR_gkl*zBj`oi}wv#I=#fvn*{B5D9_a!``_xnp{=vVU>Mz_pyrPy%oW8L4g%2!s|$pzsHn7} zVzZ(OEyngTk*}zjD+-a5@rs1CSFDei>qFK=gf)SBnXf?5+YqmAT)clgGmlqG7EFu~ zm!Ku_Dl++Fe#jqr6pa~0CE`SgmaxHm1)APEcb~+o^9P3Gc@nQsVhP%_bcl(&R-PCm zCU$#5!qyb>;J~?WHulQ%Abp3HWVQLoiLfE@IB&<{k_XRu=D5atB@cFMF_V>vJP$Uy z^B}ZH*qWUCz0AaO)?F8Gx$w{oCFm36J`gsmp-0wUeTd}2TNgC_Pd~N0ar4>_YUcd6 zZ~bb1a{mA5szp0CtvpgQC)(#)laV=vc>DeD%No~yS67s*gBI2{>>+X{AH7}Ixvc*b z>)*Mb-Z|v2dUC()=}+9Fgw>jN+SYXNcOzZIfoC=Sj~?46`|>#tC?UJBG`VxDYLT$^ zoXew6#^@t!J4KX%7Cl5SbiB%ANoHb63sDAIq#;WrN)d^i`&Eb~8Doj9mjvudRMMK9 z%VT?HVtdQ%6I1LHK}ZB|A~}TaL5qZ~$+`c1SmN$kJK8&L33-rt+j;_e>!TafP5Vd;aED1Y_}uax?dPry z1hb{pvb5NcS+Z+$zyF21N5^39DYAFo>$Fbhlq?FmlQ~b9nb>#2biZxF2A$!S(3~i_ z1U8t1o!cqx_*f^dXWK`)tK#yzKYpb(kBu6ByX+m zykV~ssnJ(wEZ-4t%lnE1v=~t>?Ogikkbmu{pES1hl~*l@_f42If9<_aS1nhtb1$9Q z^mDH~F<$!VBXpf_|LW|>eeE@E2iG=ibRxqwG9J&5%#GhzRVHA=MhVi+9eBx*pLX?C zvH#CQD>hg!XhtH5VY{1t>d3v(l#%HguMpMN-ruKV!*+nc@52XR-+q(q`W8<STfl`|)-%kCxRIg>O9#H(=T%=bQ-+56}Y zx!WFVD)xz)*(Vk@STE>Kgv-y)*^6>^hF7vnE#jc8)FM90I&X!ubH1m}Fs2|_f_h05 zvP6j@mSl`26(Wx%5;0ncF~yk29CI1xhboV~Xh0ULw(_o1hkc zmne~jeMuhST8wZK4Mq{wtPSgJhzw^i9+?yi$bQ9FV?~p_E zc~16lSFagsUpe-+jv&`F>gB2hfjsDz%K6a!P)-xad}*wG>h3_u&4jLVt7YjTindJ@ z)m{W4ku&AZM5nLv^I-NlIS)dMD+;ol=u(^qVWYDK^YdUfCg(w`1(|EROyp;^%$(I) zF3+#r?||;?mhxPi-5|NPsH=0j(>)c4&Kk_~dG@sAa}c_=^Ru)1p3@y7@75a*lWw4 zLB?F}mfE;m3M~&MmVnH;P~2a&aeviKPz%3zvH|Ag`n}KdV@b+vpr_G;uQ;?glS9TH zC7e>b2^lrLX|x1vl!=+A4*OLbcE!*_jN-j0wW>Bq*t)uD)&!rNJ9*{-eqiQl8MJVg zMZU{>K~FFEohO-kVmvw!TL=36M88mbmt&sysM@o(%Y-d~Y-!4Y_{Uv7p0RudBb=U> zKyZ%&xwBgWGado2EI~QgxM0=++47@L^SSSOtA=_p`*2o=j9G&FfZjyjy9Gfy5WhaQ zKYPM2^tLX@(ptT_v$m^*)v|KQtK`@>F823rxLoIz?zZLh0~?%`!NYK`6>N~OCEWz+ zK*+uf_izqcdIpfYH_$3eTq%CnJwsrWDBau@T9y`B^^@b?zRW+c$d%gB?ICSf36@x* z@Q^lKZbRdh^F>b?3Dnz*ARUNVnUA+zvO?poB@oYXX9;`! zU5SJQN~mS+LFVs;jW%saiN2-f_39g2UX%V_CB%B6MLD-&2x)oC^pz6OLVf5f*q|J2 z^dhW{GI7saPsT5=J6rQ0&;6*^%9tf#w*_gAn-xlGs+>y@o35OY2=?EmV=yENA#PvFiH1T$IgmHu8PY)Lmk zIuLvJo$PPC=mWaWtqo)!+>wCh@4boK_ktiDh&(cI%=P651hWimP*x)8MaVc;=wKs{ zB_$iE7tsK*9rh@f30nf0Hb7Gj#HY_l8b_~OnV|%~;Fc3Iat7a6_3&92nTLRhAlmj8B?aZ9dH7?P2zB{8GojU*$Y%R4=FHZOLHrye@irh0~=AJ?8 zvNj+yUj?s7*b>;ImbD!SIjiaYE=n{Pbm}!9XPRork1TK5P7cExJ!RQ(?)N?mO!>NW!MO3T1fVu3bK7M;R{Wb;O!X* z-qzWgssvvSp~d&XdV;rS(Bk_!meUi&d{IA+o-of?zLH3BDXci{E9`d&Pc-7V5)SbM*w@xuC@t zvwDKBdeGwCYdyhl;Go4Xw(1GnSNv`b1Z%4H6<>>?#qXi&ZCEXS4^>a_D;;RrIYw`* zUah&wzo^%aV8tt-6&p7C@XZr?;nt1>Z_HtXH}ren4m;-K#uDvazR{sxyUzEl9X57x z_7v?<0rm3T5i(yF>)XNk11%eOdwbO#2l1ssy$xm-Xz?q8dV=5FK+DFJ-d?c;gpIqb zsnl1MSt7K)zJcaks1lr`x$i~XrR^%g5)gJpF~(F0`x3`D=-i&ZQxp^vMop5;oZ4Ain15;dW+dkZ>wIh1cZ%= zjQRD1Z3pMH61r!Hggq|qcX$scJLKYi-`*O8UH*6k?-NlI%5fWse|riP=pAR#9`ea9_%RT)9KRnhls*sy2k-d^EU#PP6a&fWxlr;Sp}6ZnS` zIsG*7)g)xwS9><*;(PI$fe|eARbc~KxM%3Lv1enByB>VElGAz{4exum9QR3FEA|$r zH^DPt-XnS{uD8K40KwCJJ)t)8p4RoD-=x;H12)XNny#*T8;AzDbAVS|!S#fWbADE5 zT&X8G!(oH=>IvQ1vmPU~SMmMEH!t-gOiwge(7-%@+G0|e)ojE%m~Y1PQJ38dVH z-ez~(5L#y_^vX6kQr!e%Fm7?HMA>(FUFv*m&_Yk|0nz!YLo-7?A#0-4Z|H?TN))}o z6EuwF}7iTv$O-wkZbtz2$LFM?XO7eYJa fJF?7tM^?NW&;|&OW@rZqlu!%ppcZ8Q?%e+YL{and literal 0 HcmV?d00001 diff --git a/kuka_kr16_support/meshes/kr16_2/visual/base_link.dae b/kuka_kr16_support/meshes/kr16_2/visual/base_link.dae new file mode 100644 index 000000000..1b2b0ee9d --- /dev/null +++ b/kuka_kr16_support/meshes/kr16_2/visual/base_link.dae @@ -0,0 +1,100 @@ + + + + + Blender User + Blender 2.74.0 commit date:2015-03-31, commit time:13:39, hash:000dfc0 + + 2015-06-09T10:55:45 + 2015-06-09T10:55:45 + + Z_UP + + + + + + + + + 0 0 0 1 + + + 0 0 0 1 + + + 0.00200704 0.00200704 0.00200704 1 + + + 0.0625 0.0625 0.0625 1 + + + 10 + + + 1 + + + + + + + + + + + + + + + + -11.72107 -216.1825 396.9235 -57.91988 -208.6086 396.9235 -46.5411 -211.4384 396.9235 -80.13491 -201.1235 396.9235 80.13491 -201.1235 396.9235 90.90599 -196.4901 396.9235 -35.0258 -213.6479 396.9235 101.4104 -191.2804 396.9235 -216.1825 11.72107 396.9235 -216.5 0 396.9235 -208.6086 57.91988 396.9235 -211.4384 46.5411 396.9235 -196.4901 90.90599 396.9235 -201.1235 80.13491 396.9235 196.4901 90.90599 396.9235 191.2804 101.4104 396.9235 185.5096 111.6174 396.9235 179.1947 121.497 396.9235 205.1669 69.12879 396.9235 201.1235 80.13491 396.9235 216.5 0 396.9235 216.1825 11.72107 396.9235 69.12879 -205.1669 396.9235 11.72107 -216.1825 396.9235 23.40777 -215.2309 396.9235 0 -216.5 396.9235 -69.12879 -205.1669 396.9235 -215.2309 23.40777 396.9235 -213.6479 35.0258 396.9235 -191.2804 101.4104 396.9235 -172.3541 131.0202 396.9235 -179.1947 121.497 396.9235 211.4384 46.5411 396.9235 208.6086 57.91988 396.9235 215.2309 23.40777 396.9235 213.6479 35.0258 396.9235 216.1825 -11.72107 396.9235 140.1591 165.0081 396.9235 179.1947 -121.497 396.9235 185.5096 -111.6174 396.9235 57.91988 -208.6086 396.9235 35.0258 -213.6479 396.9235 46.5411 -211.4384 396.9235 -216.1825 -11.72107 396.9235 -215.2309 -23.40777 396.9235 -205.1669 69.12879 396.9235 -185.5096 111.6174 396.9235 11.72107 216.1825 396.9235 0 216.5 396.9235 57.91988 208.6086 396.9235 46.5411 211.4384 396.9235 101.4104 191.2804 396.9235 90.90599 196.4901 396.9235 213.6479 -35.0258 396.9235 215.2309 -23.40777 396.9235 208.6086 -57.91988 396.9235 211.4384 -46.5411 396.9235 172.3541 -131.0202 396.9235 157.178 -148.8869 396.9235 165.0081 -140.1591 396.9235 131.0202 -172.3541 396.9235 140.1591 -165.0081 396.9235 -23.40777 -215.2309 396.9235 -201.1235 -80.13491 396.9235 -196.4901 -90.90599 396.9235 -213.6479 -35.0258 396.9235 -211.4384 -46.5411 396.9235 -69.12879 205.1669 396.9235 -80.13491 201.1235 396.9235 23.40777 215.2309 396.9235 35.0258 213.6479 396.9235 80.13491 201.1235 396.9235 191.2804 -101.4104 396.9235 157.178 148.8869 396.9235 148.8869 157.178 396.9235 201.1235 -80.13491 396.9235 205.1669 -69.12879 396.9235 196.4901 -90.90599 396.9235 148.8869 -157.178 396.9235 -101.4104 -191.2804 396.9235 -90.90599 -196.4901 396.9235 -121.497 -179.1947 396.9235 -111.6174 -185.5096 396.9235 -140.1591 -165.0081 396.9235 -131.0202 -172.3541 396.9235 -165.0081 -140.1591 396.9235 -157.178 -148.8869 396.9235 -179.1947 -121.497 396.9235 -172.3541 -131.0202 396.9235 -191.2804 -101.4104 396.9235 -185.5096 -111.6174 396.9235 -205.1669 -69.12879 396.9235 -208.6086 -57.91988 396.9235 -90.90599 196.4901 396.9235 -46.5411 211.4384 396.9235 -57.91988 208.6086 396.9235 -23.40777 215.2309 396.9235 -35.0258 213.6479 396.9235 69.12879 205.1669 396.9235 121.497 179.1947 396.9235 111.6174 185.5096 396.9235 131.0202 172.3541 396.9235 165.0081 140.1591 396.9235 172.3541 131.0202 396.9235 -148.8869 -157.178 396.9235 -165.0081 140.1591 396.9235 -148.8869 157.178 396.9235 -157.178 148.8869 396.9235 -11.72107 216.1825 396.9235 121.497 -179.1947 396.9235 111.6174 -185.5096 396.9235 -140.1591 165.0081 396.9235 -121.497 179.1947 396.9235 -131.0202 172.3541 396.9235 -101.4104 191.2804 396.9235 -111.6174 185.5096 396.9235 -121.497 -179.1947 47.4 -111.6174 -185.5096 47.4 -101.4104 -191.2804 47.4 -90.90599 -196.4901 47.4 -80.13491 -201.1235 47.4 -69.12879 -205.1669 47.4 -57.91988 -208.6086 47.4 -46.5411 -211.4384 47.4 -35.0258 -213.6479 47.4 -23.40777 -215.2309 47.4 -11.72107 -216.1825 47.4 0 -216.5 47.4 11.72107 -216.1825 47.4 23.40777 -215.2309 47.4 35.0258 -213.6479 47.4 46.5411 -211.4384 47.4 57.91988 -208.6086 47.4 69.12879 -205.1669 47.4 80.13491 -201.1235 47.4 90.90599 -196.4901 47.4 101.4104 -191.2804 47.4 111.6174 -185.5096 47.4 121.497 -179.1947 47.4 131.0202 -172.3541 47.4 140.1591 -165.0081 47.4 148.8869 -157.178 47.4 157.178 -148.8869 47.4 165.0081 -140.1591 47.4 172.3541 -131.0202 47.4 179.1947 -121.497 47.4 185.5096 -111.6174 47.4 191.2804 -101.4104 47.4 196.4901 -90.90599 47.4 201.1235 -80.13491 47.4 205.1669 -69.12879 47.4 208.6086 -57.91988 47.4 211.4384 -46.5411 47.4 213.6479 -35.0258 47.4 215.2309 -23.40777 47.4 216.1825 -11.72107 47.4 216.5 0 47.4 216.1825 11.72107 47.4 215.2309 23.40777 47.4 213.6479 35.0258 47.4 211.4384 46.5411 47.4 208.6086 57.91988 47.4 205.1669 69.12879 47.4 201.1235 80.13491 47.4 196.4901 90.90599 47.4 191.2804 101.4104 47.4 185.5096 111.6174 47.4 179.1947 121.497 47.4 172.3541 131.0202 47.4 165.0081 140.1591 47.4 157.178 148.8869 47.4 148.8869 157.178 47.4 140.1591 165.0081 47.4 131.0202 172.3541 47.4 121.497 179.1947 47.4 111.6174 185.5096 47.4 101.4104 191.2804 47.4 90.90599 196.4901 47.4 80.13491 201.1235 47.4 69.12879 205.1669 47.4 57.91988 208.6086 47.4 46.5411 211.4384 47.4 35.0258 213.6479 47.4 23.40777 215.2309 47.4 11.72107 216.1825 47.4 0 216.5 47.4 -11.72107 216.1825 47.4 -23.40777 215.2309 47.4 -35.0258 213.6479 47.4 -46.5411 211.4384 47.4 -57.91988 208.6086 47.4 -69.12879 205.1669 47.4 -80.13491 201.1235 47.4 -90.90599 196.4901 47.4 -101.4104 191.2804 47.4 -111.6174 185.5096 47.4 -121.497 179.1947 47.4 -131.0202 172.3541 47.4 -169.255 135 47.4 -169.255 135 118.0245 -165.0081 140.1591 118.0245 -165.0081 140.1591 47.4 -157.178 148.8869 118.0245 -157.178 148.8869 47.4 -148.8869 157.178 118.0245 -148.8869 157.178 47.4 -140.1591 165.0081 118.0245 -132.8817 170.9231 278.0245 -132.8817 170.9231 118.0245 -140.1591 165.0081 47.4 -140.1591 165.0081 278.0245 -148.8869 157.178 278.0245 -157.178 148.8869 278.0245 -165.0081 140.1591 278.0245 -169.255 135 309 -169.255 135 278.0245 -172.3541 131.0202 309 -179.1947 121.497 309 -185.5096 111.6174 309 -191.2804 101.4104 309 -196.4901 90.90599 309 -201.1235 80.13491 309 -205.1669 69.12879 309 -208.6086 57.91988 309 -211.4384 46.5411 309 -213.6479 35.0258 309 -215.2309 23.40777 309 -216.1825 11.72107 309 -216.5 0 309 -216.1825 -11.72107 309 -215.2309 -23.40777 309 -213.6479 -35.0258 309 -211.4384 -46.5411 309 -208.6086 -57.91988 309 -205.1669 -69.12879 309 -201.1235 -80.13491 309 -196.4901 -90.90599 309 -191.2804 -101.4104 309 -185.5096 -111.6174 309 -179.1947 -121.497 309 -172.3541 -131.0202 309 -165.0081 -140.1591 278.0245 -169.255 -135 309 -157.178 -148.8869 278.0245 -148.8869 -157.178 278.0245 -140.1591 -165.0081 278.0245 -140.1591 -165.0081 47.4 -131.0202 -172.3541 47.4 -132.8817 -170.9231 118.0245 -132.8817 -170.9231 278.0245 -140.1591 -165.0081 118.0245 -148.8869 -157.178 118.0245 -148.8869 -157.178 47.4 -157.178 -148.8869 118.0245 -157.178 -148.8869 47.4 -165.0081 -140.1591 118.0245 -169.255 -135 118.0245 -169.255 -135 47.4 -165.0081 -140.1591 47.4 -169.255 -135 278.0245 -290.5 135 309 -290.5 135 278.0245 -290.5 -135 278.0245 -290.5 -135 309 -132.8817 226.559 118.0245 -132.8817 226.559 278.0245 -292.8817 226.559 118.0245 -292.8817 226.559 278.0245 -292.8817 134.999 278.0245 -290.5 134.999 278.0245 -292.8817 134.999 118.0245 -290.5 135 118.0245 -290.5 134.999 118.0245 -132.8817 -226.56 118.0245 -132.8817 -226.56 278.0245 -292.8817 -226.56 118.0245 -292.8817 -226.56 278.0245 -292.8817 -135 278.0245 -290.5 -135 118.0245 -292.8817 -135 118.0245 -231.0689 -135 43.85897 -213.1817 -135 47.4 -290.5 -135 32 -231.0689 -135 32 -213.1817 135 47.4 -290.5 135 32 -231.0689 135 43.85897 -231.0689 135 32 -231.0689 129.5 32 -231.0689 -129.5 32 -46.5 -129.5 32 -46.5 129.5 32 -46.5 129.5 47.4 -46.5 -129.5 47.4 -36.06889 -129.5 47.4 -36.06889 129.5 47.4 -231.0689 129.5 6 -36.06889 129.5 6 -36.06889 -129.5 6 -231.0689 -129.5 6 -231.0689 147.1001 39.71003 -231.0689 147.1001 6 -231.0689 -147.1001 6 -231.0689 -147.1001 39.71003 -222.3874 179.5 30.31927 -222.3874 179.5 6 -197.0662 179.5 6 -197.0662 179.5 35.33194 -197.0662 179.5016 35.33141 -197.0662 179.5016 6 -186.6279 218.4582 24.04025 -186.6279 218.4582 6 -100.8189 268 6 -100.8189 268 24.04025 -222.2534 -180 6 -222.2534 -180 30.17435 -197.0684 -180 6 -197.0684 -180 35.16008 -197.0684 -180.0003 6 -197.0684 -180.0003 35.15996 -186.7885 -218.3654 6 -186.7885 -218.3654 24.04025 -100.8189 -268 6 -100.8189 -268 24.04025 -154.1874 -169.0604 47.4 -100.6726 -268 24.06921 -183.6508 -220.0925 24.06921 -100.6726 -268 24 -183.6508 -220.0925 24 -154.1508 -168.997 24 -154.1508 -168.997 47.4 -69.28031 -217.997 47.4 -69.28031 -217.997 24 -98.14955 -268 24 -98.14955 -268 24.56868 -69.31689 -218.0604 47.4 -43.47426 -268 6 -43.47426 -268 35.39242 -9.919786 -252.3533 47.4 138.8448 -182.9832 6 138.8448 -182.9832 47.4 -154.1874 169.0604 47.4 -183.6508 220.0925 24.06921 -100.6726 268 24.06921 -183.6508 220.0925 24 -100.6726 268 24 -154.1508 168.997 24 -154.1508 168.997 47.4 -69.28031 217.997 47.4 -69.28031 217.997 24 -69.31688 218.0604 47.4 -98.14955 268 24.56868 -98.14955 268 24 -43.47426 268 35.39242 -43.47426 268 6 -9.919786 252.3533 47.4 138.8448 182.9832 6 138.8448 182.9832 47.4 -145.6637 196.4888 24 -121.4629 205.0395 24 -116.2034 224.6684 24 -114.6077 222.5063 24 -118.2402 226.4212 24 -119 206.114 24 -115.0851 209.7465 24 -116.8379 207.7097 24 -113.0336 217.4031 24 -113.134 214.7178 24 -133.7966 208.3443 24 -135.3923 210.5063 24 -147.2994 201.186 24 -146.1849 198.9407 24 -126.7885 204.6404 24 -129.3841 205.3359 24 -124.1032 204.5399 24 -120.6159 227.6768 24 -125.8968 228.4728 24 -123.2115 228.3723 24 -131 226.8986 24 -128.5371 227.9732 24 -163.1986 189.1178 24 -164.5858 191.2057 24 -113.8295 212.1222 24 -131.7598 206.5915 24 -148.9373 203.0835 24 -136.9664 215.6096 24 -136.866 218.2949 24 -150.9957 204.5141 24 -134.9149 223.2662 24 -158.3179 205.2837 24 -164.1823 200.8323 24 -162.6253 202.7968 24 -165.6199 196.0708 24 -165.2019 198.5424 24 -149.5827 187.6867 24 -150.6287 186.9918 24 -147.7917 189.4406 24 -136.4669 212.9693 24 -133.1621 225.303 24 -136.1705 220.8904 24 -160.6287 204.3123 24 -165.4101 193.5729 24 -159.1144 186.2792 24 -161.3358 187.4405 24 -113.5331 220.0434 24 -151.7535 186.4334 24 -145.7687 193.9843 24 -146.4932 191.5847 24 -155.8381 205.6498 24 -153.3451 205.3878 24 -154.1678 185.7593 24 -156.6739 185.7068 24 -133.1621 225.303 0 -131 226.8986 0 -134.9149 223.2662 0 -136.1705 220.8904 0 -136.866 218.2949 0 -137 216.5063 0 -136.9664 215.6096 0 -136.4669 212.9693 0 -135.3923 210.5063 0 -133.7966 208.3443 0 -131.7598 206.5915 0 -129.3841 205.3359 0 -126.7885 204.6404 0 -124.1032 204.5399 0 -121.4629 205.0395 0 -119 206.114 0 -116.8379 207.7097 0 -115.0851 209.7465 0 -113.8295 212.1222 0 -113.134 214.7178 0 -113.0336 217.4031 0 -113.5331 220.0434 0 -114.6077 222.5063 0 -116.2034 224.6684 0 -118.2402 226.4212 0 -120.6159 227.6768 0 -123.2115 228.3723 0 -125.8968 228.4728 0 -128.5371 227.9732 0 -162.6253 202.7968 0 -160.6287 204.3123 0 -164.1823 200.8323 0 -165.2019 198.5424 0 -165.6199 196.0708 0 -165.4101 193.5729 0 -165.6287 195.652 0 -164.5858 191.2057 0 -163.1986 189.1178 0 -161.3358 187.4405 0 -159.1144 186.2792 0 -156.6739 185.7068 0 -154.1678 185.7593 0 -151.7535 186.4334 0 -149.5827 187.6867 0 -147.7917 189.4406 0 -146.4932 191.5847 0 -145.7687 193.9843 0 -145.6637 196.4888 0 -146.1849 198.9407 0 -147.2994 201.186 0 -148.9373 203.0835 0 -150.9957 204.5141 0 -153.3451 205.3878 0 -155.8381 205.6498 0 -158.3179 205.2837 0 -118.2402 -226.4212 24 -98.62194 -239.7491 24 -116.2034 -224.6684 24 -100.179 -237.7847 24 -129.3841 -205.3359 24 -126.7885 -204.6404 24 -131 -226.8986 24 -114.6077 -222.5063 24 -124.1032 -204.5399 24 -121.4629 -205.0395 24 -131.7598 -206.5915 24 -135.3923 -210.5063 24 -133.7966 -208.3443 24 -136.4669 -212.9693 24 -128.5371 -227.9732 24 -113.5331 -220.0434 24 -136.866 -218.2949 24 -136.9664 -215.6096 24 -134.9149 -223.2662 24 -136.1705 -220.8904 24 -133.1621 -225.303 24 -123.2115 -228.3723 24 -125.8968 -228.4728 24 -120.6159 -227.6768 24 -113.0336 -217.4031 24 -97.33245 -224.3929 24 -116.8379 -207.7097 24 -87.75016 -223.3858 24 -86.62531 -223.9441 24 -119 -206.114 24 -85.57932 -224.6391 24 -90.16448 -222.7117 24 -94.31451 -242.236 24 -82.48986 -228.537 24 -81.76535 -230.9367 24 -99.19526 -226.0702 24 -91.83473 -242.6022 24 -82.18154 -235.893 24 -83.2961 -238.1383 24 -115.0851 -209.7465 24 -113.8295 -212.1222 24 -83.78838 -226.3929 24 -92.6706 -222.6592 24 -95.11103 -223.2316 24 -96.62531 -241.2646 24 -86.99235 -241.4664 24 -89.3418 -242.3402 24 -81.66038 -233.4412 24 -113.134 -214.7178 24 -84.934 -240.0358 24 -101.1985 -235.4947 24 -101.6165 -233.0231 24 -101.4068 -230.5253 24 -100.5824 -228.158 24 -128.5371 -227.9732 0 -131 -226.8986 0 -125.8968 -228.4728 0 -123.2115 -228.3723 0 -120.6159 -227.6768 0 -118.2402 -226.4212 0 -116.2034 -224.6684 0 -114.6077 -222.5063 0 -113.5331 -220.0434 0 -113.0336 -217.4031 0 -113.134 -214.7178 0 -113.8295 -212.1222 0 -115.0851 -209.7465 0 -116.8379 -207.7097 0 -119 -206.114 0 -121.4629 -205.0395 0 -124.1032 -204.5399 0 -126.7885 -204.6404 0 -129.3841 -205.3359 0 -131.7598 -206.5915 0 -133.7966 -208.3443 0 -135.3923 -210.5063 0 -136.4669 -212.9693 0 -136.9664 -215.6096 0 -136.866 -218.2949 0 -137 -216.5063 0 -136.1705 -220.8904 0 -134.9149 -223.2662 0 -133.1621 -225.303 0 -94.31451 -242.236 0 -96.62531 -241.2646 0 -91.83473 -242.6022 0 -89.3418 -242.3402 0 -86.99235 -241.4664 0 -84.934 -240.0358 0 -83.2961 -238.1383 0 -82.18154 -235.893 0 -81.66038 -233.4412 0 -81.76535 -230.9367 0 -82.48986 -228.537 0 -83.78838 -226.3929 0 -85.57932 -224.6391 0 -87.75016 -223.3858 0 -90.16448 -222.7117 0 -92.6706 -222.6592 0 -95.11103 -223.2316 0 -97.33245 -224.3929 0 -99.19526 -226.0702 0 -100.5824 -228.158 0 -101.4068 -230.5253 0 -101.6253 -232.6044 0 -101.6165 -233.0231 0 -101.1985 -235.4947 0 -100.179 -237.7847 0 -98.62194 -239.7491 0 282.4311 62.5 6 223.4311 112.0069 47.4 282.4311 62.5 24.04025 282.4311 -62.5 6 282.4311 -62.5 24.04025 223.4311 -112.0069 47.4 223.4311 -49 47.4 223.4311 49 47.4 282.4311 -49 24.04025 282.4311 49 24.04025 282.4311 -49 24 282.4311 49 24 223.4311 -49 24 223.4311 49 24 239.1884 -5.206605 24 238.3009 -2.670251 24 244.7934 -10.81163 24 242.5181 -9.381978 24 250 -12 24 247.3297 -11.69913 24 252.6703 -11.69913 24 237.3328 35.69902 24 237.254 36.95235 24 237.9562 33.27111 24 240.618 -7.481878 24 255.2066 -10.81163 24 259.382 -7.481878 24 257.4819 -9.381978 24 237.3328 38.20568 24 242.9962 27.90408 24 238.3009 2.670251 24 261.6991 -2.670251 24 260.8116 -5.206605 24 237.9562 40.6336 24 238 0 24 254.5437 30.10688 24 242.5181 9.381978 24 244.7934 10.81163 24 257.4819 9.381978 24 257.254 36.95235 24 239.1638 31.0745 24 262 0 24 245.3802 27.12948 24 239.1884 5.206605 24 252.6703 11.69913 24 256.017 32.13481 24 247.3297 11.69913 24 240.618 7.481878 24 256.9398 39.43925 24 247.8819 46.93262 24 250.3441 46.46292 24 245.3802 46.77523 24 240.8797 44.65748 24 242.9962 46.00062 24 239.1638 42.8302 24 240.8797 29.24722 24 250.3441 27.44179 24 247.8819 26.97209 24 252.6122 28.50907 24 250 12 24 259.382 7.481878 24 260.8116 5.206605 24 255.2066 10.81163 24 252.6122 45.39563 24 254.5437 43.79782 24 256.9398 34.46545 24 261.6991 2.670251 24 256.017 41.76989 24 256.9398 39.43925 0 257.254 36.95235 0 256.017 41.76989 0 254.5437 43.79782 0 252.6122 45.39563 0 250.3441 46.46292 0 247.8819 46.93262 0 245.3802 46.77523 0 242.9962 46.00062 0 240.8797 44.65748 0 239.1638 42.8302 0 237.9562 40.6336 0 237.3328 38.20568 0 237.3328 35.69902 0 237.254 36.95235 0 237.9562 33.27111 0 239.1638 31.0745 0 240.8797 29.24722 0 242.9962 27.90408 0 245.3802 27.12948 0 247.8819 26.97209 0 250.3441 27.44179 0 252.6122 28.50907 0 254.5437 30.10688 0 256.017 32.13481 0 256.9398 34.46545 0 261.6991 2.670251 0 262 0 0 260.8116 5.206605 0 259.382 7.481878 0 257.4819 9.381978 0 255.2066 10.81163 0 252.6703 11.69913 0 250 12 0 247.3297 11.69913 0 244.7934 10.81163 0 242.5181 9.381978 0 240.618 7.481878 0 239.1884 5.206605 0 238.3009 2.670251 0 238 0 0 238.3009 -2.670251 0 239.1884 -5.206605 0 240.618 -7.481878 0 242.5181 -9.381978 0 244.7934 -10.81163 0 247.3297 -11.69913 0 250 -12 0 252.6703 -11.69913 0 255.2066 -10.81163 0 257.4819 -9.381978 0 259.382 -7.481878 0 260.8116 -5.206605 0 261.6991 -2.670251 0 -290.5 -114.8659 278.0245 -290.5 -114.8659 113.0245 -290.5 115.1341 113.0245 -290.5 115.1341 278.0245 -297.9 -114.8659 113.0245 -297.9 115.1341 113.0245 -297.9 115.1341 278.0245 -297.9 -114.8659 278.0245 -292.8817 155.059 129.0245 -292.8817 199.059 129.0245 -292.8817 155.059 269.0245 -292.8817 199.059 269.0245 -297.8817 199.059 129.0245 -297.8817 155.059 129.0245 -297.8817 155.059 269.0245 -297.8817 199.059 269.0245 -297.8817 199.059 259.0245 -297.8817 155.059 259.0245 -297.8817 155.059 139.0245 -297.8817 199.059 139.0245 -326.8817 199.059 259.0245 -326.8817 155.059 259.0245 -348.8817 155.059 139.0245 -348.8817 199.059 139.0245 -326.8817 199.059 280.5245 -326.8817 155.059 280.5245 -332.8817 199.059 286.5245 -332.8817 155.059 286.5245 -341.4758 199.059 286.5245 -341.4758 155.059 286.5245 -346.9552 199.059 281.0451 -346.9552 155.059 281.0451 -348.8817 155.059 259.0245 -348.8817 199.059 259.0245 -398.8817 199.059 149.0154 -398.8817 199.059 249.0335 -398.8817 155.059 149.0154 -398.8817 155.059 249.0335 -354.8129 177.059 140.2096 -355.9957 170.2186 140.446 -355.1109 173.5861 140.2692 -374.4252 157.059 144.1286 -389.4491 164.2033 147.1306 -387.0317 161.7382 146.6476 -392.8547 170.2186 147.8111 -391.41 167.059 147.5224 -389.4491 189.9148 147.1306 -391.41 187.059 147.5224 -381.133 195.8529 145.4689 -384.2313 194.3796 146.088 -371.0196 196.7552 143.448 -374.4252 197.059 144.1286 -355.1109 180.532 140.2692 -355.9957 183.8995 140.446 -359.4013 164.2033 141.1265 -357.4404 167.059 140.7347 -364.6191 159.7385 142.1691 -361.8186 161.7382 141.6095 -371.0196 157.3629 143.448 -367.7174 158.2652 142.7882 -377.8309 157.3629 144.8091 -384.2313 159.7385 146.088 -381.133 158.2652 145.4689 -387.0317 192.3799 146.6476 -377.8309 196.7552 144.8091 -364.6191 194.3796 142.1691 -367.7174 195.8529 142.7882 -359.4013 189.9148 141.1265 -361.8186 192.3799 141.6095 -394.0375 177.059 148.0475 -357.4404 187.059 140.7347 -393.7395 173.5861 147.9879 -392.8547 183.8995 147.8111 -393.7395 180.532 147.9879 -362.9487 173.5861 101.0446 -362.6507 177.059 100.985 -363.8335 170.2186 101.2214 -365.2783 167.059 101.5101 -367.2391 164.2033 101.9019 -369.6565 161.7382 102.3849 -372.4569 159.7385 102.9445 -375.5552 158.2652 103.5636 -378.8574 157.3629 104.2235 -382.263 157.059 104.904 -385.6687 157.3629 105.5845 -388.9708 158.2652 106.2443 -392.0692 159.7385 106.8634 -394.8696 161.7382 107.423 -397.2869 164.2033 107.906 -399.2478 167.059 108.2979 -400.6926 170.2186 108.5866 -401.5774 173.5861 108.7633 -401.8753 177.059 108.8229 -401.5774 180.532 108.7633 -400.6926 183.8995 108.5866 -399.2478 187.059 108.2979 -397.2869 189.9148 107.906 -394.8696 192.3799 107.423 -392.0692 194.3796 106.8634 -388.9708 195.8529 106.2443 -385.6687 196.7552 105.5845 -382.263 197.059 104.904 -378.8574 196.7552 104.2235 -375.5552 195.8529 103.5636 -372.4569 194.3796 102.9445 -369.6565 192.3799 102.3849 -367.2391 189.9148 101.9019 -365.2783 187.059 101.5101 -363.8335 183.8995 101.2214 -362.9487 180.532 101.0446 -292.8817 -158.4697 248.9499 -292.8817 -159.559 249.0245 -292.8817 -151.7264 239.3968 -292.8817 -155.4024 234.1891 -292.8817 -153.7124 235.564 -292.8817 -177.3081 227.7745 -292.8817 -163.7157 234.1891 -292.8817 -156.3718 248.3621 -292.8817 -152.021 243.7035 -292.8817 -153.0233 245.6379 -292.8817 -151.5777 241.5704 -292.8817 -152.456 237.3439 -292.8817 -159.559 233.0245 -292.8817 -157.4007 233.3211 -292.8817 -161.7174 233.3211 -292.8817 -177.3081 254.2745 -292.8817 -167.5404 241.5704 -292.8817 -154.5103 247.2301 -292.8817 -165.4057 235.564 -292.8817 -167.0971 243.7035 -292.8817 -166.0948 245.6379 -292.8817 -160.6484 248.9499 -292.8817 -167.3917 239.3968 -292.8817 -166.6621 237.3439 -292.8817 -164.6078 247.2301 -292.8817 -162.7463 248.3621 -292.8817 -203.8081 227.7745 -292.8817 -203.8081 254.2745 -295.3817 -177.3081 227.7745 -295.3817 -203.8081 227.7745 -295.3817 -177.3081 254.2745 -295.3817 -203.8081 254.2745 -295.3817 -179.0724 234.9351 -295.3817 -178.0319 237.5466 -295.3817 -187.7635 228.3284 -295.3817 -185.0995 229.226 -295.3817 -181.618 250.4624 -295.3817 -183.8559 252.1636 -295.3817 -178.4814 245.8363 -295.3817 -179.7981 248.3199 -295.3817 -180.65 232.6084 -295.3817 -182.6908 230.6752 -295.3817 -193.3527 228.3284 -295.3817 -190.5581 228.0245 -295.3817 -202.0438 234.9351 -295.3817 -200.4662 232.6084 -295.3817 -203.539 240.3206 -295.3817 -203.0843 237.5466 -295.3817 -186.4072 253.3439 -295.3817 -189.1526 253.9483 -295.3817 -177.5772 240.3206 -295.3817 -198.4254 230.6752 -295.3817 -196.0167 229.226 -295.3817 -199.4982 250.4624 -295.3817 -201.3181 248.3199 -295.3817 -194.709 253.3439 -295.3817 -197.2603 252.1636 -295.3817 -190.5581 254.0245 -295.3817 -177.7294 243.1276 -295.3817 -203.3869 243.1276 -295.3817 -191.9636 253.9483 -295.3817 -202.6348 245.8363 -300.3817 -161.7174 233.3211 -300.3817 -159.559 233.0245 -300.3817 -163.7157 234.1891 -300.3817 -165.4057 235.564 -300.3817 -166.6621 237.3439 -300.3817 -167.3917 239.3968 -300.3817 -167.5404 241.5704 -300.3817 -167.0971 243.7035 -300.3817 -166.0948 245.6379 -300.3817 -164.6078 247.2301 -300.3817 -162.7463 248.3621 -300.3817 -160.6484 248.9499 -300.3817 -158.4697 248.9499 -300.3817 -159.559 249.0245 -300.3817 -156.3718 248.3621 -300.3817 -154.5103 247.2301 -300.3817 -153.0233 245.6379 -300.3817 -152.021 243.7035 -300.3817 -151.5777 241.5704 -300.3817 -151.7264 239.3968 -300.3817 -152.456 237.3439 -300.3817 -153.7124 235.564 -300.3817 -155.4024 234.1891 -300.3817 -157.4007 233.3211 -334.8917 -202.6348 245.8363 -334.8917 -203.3869 243.1276 -334.8917 -201.3181 248.3199 -334.8917 -199.4982 250.4624 -334.8917 -197.2603 252.1636 -334.8917 -194.709 253.3439 -334.8917 -191.9636 253.9483 -334.8917 -189.1526 253.9483 -334.8917 -190.5581 254.0245 -334.8917 -186.4072 253.3439 -334.8917 -183.8559 252.1636 -334.8917 -181.618 250.4624 -334.8917 -179.7981 248.3199 -334.8917 -178.4814 245.8363 -334.8917 -177.7294 243.1276 -310.5286 -203.3869 238.9213 -309.1539 -203.0843 237.5466 -311.9309 -203.501 240.3236 -307.8199 -202.6348 236.2127 -306.5424 -202.0438 234.9351 -305.3363 -201.3181 233.729 -304.2157 -200.4662 232.6084 -303.1938 -199.4982 231.5865 -302.2825 -198.4254 230.6752 -301.4926 -197.2603 229.8853 -300.8332 -196.0167 229.226 -300.3122 -194.709 228.705 -299.9356 -193.3527 228.3284 -299.7079 -191.9636 228.1007 -299.6317 -190.5581 228.0245 -299.7079 -189.1526 228.1007 -299.9356 -187.7635 228.3284 -300.3122 -186.4072 228.705 -300.8332 -185.0995 229.226 -301.4926 -183.8559 229.8853 -302.2825 -182.6908 230.6752 -303.1938 -181.618 231.5865 -304.2157 -180.65 232.6084 -305.3363 -179.7981 233.729 -306.5424 -179.0724 234.9351 -307.8199 -178.4814 236.2127 -309.1539 -178.0319 237.5466 -310.5286 -177.7294 238.9213 -312.6317 -177.5581 241.0245 -313.3326 -177.6152 240.3236 -311.9279 -177.5772 240.3206 -334.8917 -177.5772 240.3206 -314.7349 -177.7294 238.9213 -316.1096 -178.0319 237.5466 -334.8917 -178.0319 237.5466 -317.4435 -178.4814 236.2127 -318.721 -179.0724 234.9351 -334.8917 -179.0724 234.9351 -319.9272 -179.7981 233.729 -321.0477 -180.65 232.6084 -334.8917 -180.65 232.6084 -322.0697 -181.618 231.5865 -322.9809 -182.6908 230.6752 -334.8917 -182.6908 230.6752 -323.7709 -183.8559 229.8853 -324.4302 -185.0995 229.226 -334.8917 -185.0995 229.226 -324.9512 -186.4072 228.705 -325.3278 -187.7635 228.3284 -334.8917 -190.5581 228.0245 -334.8917 -187.7635 228.3284 -325.5555 -189.1526 228.1007 -325.6317 -190.5581 228.0245 -325.5555 -191.9636 228.1007 -334.8917 -193.3527 228.3284 -334.8917 -196.0167 229.226 -325.3278 -193.3527 228.3284 -324.9512 -194.709 228.705 -334.8917 -198.4254 230.6752 -324.4302 -196.0167 229.226 -323.7709 -197.2603 229.8853 -334.8917 -200.4662 232.6084 -322.9809 -198.4254 230.6752 -322.0697 -199.4982 231.5865 -334.8917 -202.0438 234.9351 -321.0477 -200.4662 232.6084 -319.9272 -201.3181 233.729 -334.8917 -203.0843 237.5466 -318.721 -202.0438 234.9351 -317.4435 -202.6348 236.2127 -334.8917 -203.539 240.3206 -316.1096 -203.0843 237.5466 -314.7349 -203.3869 238.9213 -312.6317 -203.5581 241.0245 -313.3326 -203.501 240.3236 -314.7349 -203.3869 204.7745 -317.4435 -202.6348 204.7745 -319.9272 -201.3181 204.7745 -322.0697 -199.4982 204.7745 -323.7709 -197.2603 204.7745 -324.9512 -194.709 204.7745 -325.5555 -189.1526 204.7745 -325.6317 -190.5581 204.7745 -325.5555 -191.9636 204.7745 -324.9512 -186.4072 204.7745 -323.7709 -183.8559 204.7745 -322.0697 -181.618 204.7745 -319.9272 -179.7981 204.7745 -317.4435 -178.4814 204.7745 -314.7349 -177.7294 204.7745 -311.9279 -177.5772 204.7745 -309.1539 -178.0319 204.7745 -306.5424 -179.0724 204.7745 -304.2157 -180.65 204.7745 -302.2825 -182.6908 204.7745 -300.8332 -185.0995 204.7745 -299.9356 -187.7635 204.7745 -299.9356 -193.3527 204.7745 -299.6317 -190.5581 204.7745 -300.8332 -196.0167 204.7745 -302.2825 -198.4254 204.7745 -304.2157 -200.4662 204.7745 -306.5424 -202.0438 204.7745 -309.1539 -203.0843 204.7745 -311.9279 -203.539 204.7745 -88.70153 247.3021 0 -73.10583 243.934 0 -76.55937 227.9165 0 -158.9123 230.4548 0 -120.1236 252.8495 0 -104.3774 250.2746 0 -164.5555 215.5308 0 -79.59553 211.8148 0 -82.21228 195.6396 0 -159.1018 180.2606 0 -174.7001 185.2785 0 -169.8192 200.4688 0 -128.3227 169.0177 0 -143.6392 174.8392 0 -82.21228 195.6396 6 -128.3227 169.0177 6 -76.55937 227.9165 6 -79.59553 211.8148 6 -73.10583 243.934 6 -104.3774 250.2746 6 -88.70153 247.3021 6 -120.1236 252.8495 6 -158.9123 230.4548 6 -169.8192 200.4688 6 -164.5555 215.5308 6 -174.7001 185.2785 6 -143.6392 174.8392 6 -159.1018 180.2606 6 279.0359 -22.39472 0 268.9329 -34.7438 0 258.5207 -46.8333 0 223.2348 -36.97566 0 247.8059 -58.65547 0 235.6612 -47.65592 0 210.535 -26.62189 0 258.5207 46.8333 0 268.9329 34.7438 0 279.0359 22.39472 0 210.535 26.62189 0 235.6612 47.65592 0 247.8059 58.65547 0 223.2348 36.97566 0 210.535 -26.62189 6 210.535 26.62189 6 235.6612 -47.65592 6 223.2348 -36.97566 6 247.8059 -58.65547 6 268.9329 -34.7438 6 258.5207 -46.8333 6 279.0359 -22.39472 6 279.0359 22.39472 6 258.5207 46.8333 6 268.9329 34.7438 6 247.8059 58.65547 6 223.2348 36.97566 6 235.6612 47.65592 6 -82.21228 -195.6396 6 -79.59553 -211.8148 6 -174.7001 -185.2785 6 -76.55937 -227.9165 6 -73.10583 -243.934 6 -169.8192 -200.4688 6 -88.70153 -247.3021 6 -104.3774 -250.2746 6 -158.9123 -230.4548 6 -164.5555 -215.5308 6 -128.3227 -169.0177 6 -120.1236 -252.8495 6 -159.1018 -180.2606 6 -143.6392 -174.8392 6 -158.9123 -230.4548 0 -164.5555 -215.5308 0 -143.6392 -174.8392 0 -128.3227 -169.0177 0 -73.10583 -243.934 0 -88.70153 -247.3021 0 -169.8192 -200.4688 0 -174.7001 -185.2785 0 -159.1018 -180.2606 0 -76.55937 -227.9165 0 -104.3774 -250.2746 0 -82.21228 -195.6396 0 -79.59553 -211.8148 0 -120.1236 -252.8495 0 -242.1312 14.98807 309 -240.4476 55.31908 309 -243.6149 56.24073 309 -230.7122 56.24073 309 -233.8795 55.31908 309 -266.9026 29.98807 309 -249.1575 59.76477 309 -251.3359 62.24193 309 -246.5531 57.74039 309 -237.1636 55.00818 309 -227.7741 57.74039 309 -222.9913 62.24193 309 -225.1696 59.76477 309 -221.3165 65.08388 309 -226.0582 86.03302 309 -223.7175 83.70872 309 -288.4026 59.98807 309 -254.52 74.74562 309 -253.7917 77.96295 309 -220.2048 68.18962 309 -221.8545 80.98645 309 -266.9026 59.98807 309 -242.1312 -15.01193 309 -219.6957 71.4488 309 -220.5354 77.96295 309 -219.8072 74.74562 309 -228.3161 87.60694 309 -254.6315 71.4488 309 -253.0106 65.08388 309 -250.6097 83.70872 309 -248.2689 86.03302 309 -252.4727 80.98645 309 -266.9026 -30.01193 309 -246.011 87.60694 309 -266.9026 -60.01193 309 -254.1223 68.18962 309 -288.4026 -30.01193 309 -272.1312 -15.01193 309 -272.1312 14.98807 309 -288.4026 29.98807 309 -288.4026 -60.01193 309 -266.9026 -30.01193 311.7 -266.9026 -60.01193 311.7 -288.4026 -30.01193 311.7 -288.4026 -60.01193 311.7 -266.9026 59.98807 311.7 -266.9026 29.98807 311.7 -288.4026 59.98807 311.7 -288.4026 29.98807 311.7 -242.1312 14.98807 317 -242.1312 -15.01193 317 -255 14.98807 317 -255 -15.01193 317 -255 -15.01193 311.7 -272.1312 -15.01193 311.7 -255 14.98807 311.7 -272.1312 14.98807 311.7 -246.2908 86.82627 323.8962 -228.0363 86.82627 323.8962 -228.1715 87.21965 316.3902 -246.1556 87.21965 316.3902 -227.9107 86.42723 331.5103 -246.4164 86.42723 331.5103 -227.7948 86.02294 339.2245 -246.5324 86.02294 339.2245 -227.6887 85.61385 347.0306 -227.5925 85.20035 354.9205 -246.6385 85.61385 347.0306 -227.5064 84.7829 362.886 -246.7346 85.20035 354.9205 -227.4308 84.36209 370.9155 -246.8208 84.7829 362.886 -246.9019 84.33146 371.5 -227.4253 84.33146 371.5 -246.8968 84.36193 370.9186 -225.3944 82.31182 371.5 -223.7638 79.92907 371.5 -222.6092 77.28264 371.5 -221.9718 74.46658 371.5 -221.8742 71.58092 371.5 -222.3199 68.72821 371.5 -223.2929 66.00981 371.5 -224.7588 63.52231 371.5 -226.6655 61.35409 371.5 -228.9451 59.58219 371.5 -231.5168 58.26956 371.5 -234.2891 57.46286 371.5 -237.1636 57.19073 371.5 -240.038 57.46286 371.5 -242.8103 58.26956 371.5 -245.382 59.58219 371.5 -247.6617 61.35409 371.5 -249.5684 63.52231 371.5 -251.0343 66.00981 371.5 -252.0073 68.72821 371.5 -252.4529 71.58092 371.5 -252.3553 74.46658 371.5 -251.7179 77.28264 371.5 -250.5634 79.92907 371.5 -248.9327 82.31182 371.5 + + + + + + + + + + 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 -0.5833953 -0.8121884 0 -0.5385679 -0.8425822 0 -0.492162 -0.8705036 0 -0.4443113 -0.8958724 0 -0.3951582 -0.9186131 0 -0.3448467 -0.938659 0 -0.2935216 -0.9559525 0 -0.2413387 -0.9704409 0 -0.1884456 -0.9820836 0 -0.1349992 -0.9908457 0 -0.08115851 -0.9967013 0 -0.0270797 -0.9996333 0 0.0270797 -0.9996333 0 0.08115851 -0.9967013 0 0.1349992 -0.9908457 0 0.1884456 -0.9820836 0 0.2413387 -0.9704409 0 0.2935216 -0.9559525 0 0.3448467 -0.938659 0 0.3951582 -0.9186131 0 0.4443113 -0.8958724 0 0.492162 -0.8705036 0 0.5385679 -0.8425822 0 0.5833953 -0.8121884 0 0.6265094 -0.7794139 0 0.667788 -0.7443515 0 0.7071068 -0.7071068 0 0.7443515 -0.667788 0 0.7794139 -0.6265094 0 0.8121884 -0.5833953 0 0.8425822 -0.5385679 0 0.8705036 -0.492162 0 0.8958724 -0.4443113 0 0.9186131 -0.3951582 0 0.938659 -0.3448467 0 0.9559525 -0.2935216 0 0.9704409 -0.2413387 0 0.9820836 -0.1884456 0 0.9908457 -0.1349992 0 0.9967013 -0.08115851 0 0.9996333 -0.0270797 0 0.9996333 0.0270797 0 0.9967013 0.08115851 0 0.9908457 0.1349992 0 0.9820836 0.1884456 0 0.9704409 0.2413387 0 0.9559525 0.2935216 0 0.938659 0.3448467 0 0.9186131 0.3951582 0 0.8958724 0.4443113 0 0.8705036 0.492162 0 0.8425822 0.5385679 0 0.8121884 0.5833953 0 0.7794139 0.6265094 0 0.7443515 0.667788 0 0.7071068 0.7071068 0 0.667788 0.7443515 0 0.6265094 0.7794139 0 0.5833953 0.8121884 0 0.5385679 0.8425822 0 0.492162 0.8705036 0 0.4443113 0.8958724 0 0.3951582 0.9186131 0 0.3448467 0.938659 0 0.2935216 0.9559525 0 0.2413387 0.9704409 0 0.1884456 0.9820836 0 0.1349992 0.9908457 0 0.08115851 0.9967013 0 0.0270797 0.9996333 0 -0.0270797 0.9996333 0 -0.08115851 0.9967013 0 -0.1349992 0.9908457 0 -0.1884456 0.9820836 0 -0.2413387 0.9704409 0 -0.2935216 0.9559525 0 -0.3448467 0.938659 0 -0.3951582 0.9186131 0 -0.4443113 0.8958724 0 -0.492162 0.8705036 0 -0.5385679 0.8425822 0 -0.5833953 0.8121884 0 -0.7720621 0.6355471 0 -0.7443516 0.667788 0 -0.7071068 0.7071068 0 -0.667788 0.7443516 0 -0.6265093 0.7794138 4.27724e-4 -0.6094809 0.7928008 0 -0.6094809 0.7928009 0 -0.6307269 0.776005 0 -0.6265092 0.7794137 -7.20091e-4 -0.667788 0.7443515 0 -0.7071068 0.7071068 0 -0.7443515 0.667788 0 -0.7794135 0.6265091 8.85416e-4 -0.7720621 0.6355471 0 -0.7720621 0.6355471 0 -0.8121884 0.5833953 0 -0.8425822 0.5385679 0 -0.8705036 0.492162 0 -0.8958725 0.4443113 0 -0.918613 0.3951582 0 -0.938659 0.3448467 0 -0.9559525 0.2935216 0 -0.9704409 0.2413387 0 -0.9820836 0.1884456 0 -0.9908457 0.1349992 0 -0.9967012 0.08115851 0 -0.9996333 0.0270797 0 -0.9996333 -0.0270797 0 -0.9967012 -0.08115851 0 -0.9908457 -0.1349992 0 -0.9820836 -0.1884456 0 -0.9704409 -0.2413387 0 -0.9559525 -0.2935216 0 -0.938659 -0.3448467 0 -0.918613 -0.3951582 0 -0.8958725 -0.4443113 0 -0.8705036 -0.492162 0 -0.8425822 -0.5385679 0 -0.8121884 -0.5833953 0 -0.7720621 -0.6355471 0 -0.7889903 -0.6144056 0 -0.7794135 -0.6265091 8.85416e-4 -0.7443515 -0.667788 0 -0.7071068 -0.7071068 0 -0.667788 -0.7443515 0 -0.6265092 -0.7794137 -7.20091e-4 -0.6094809 -0.7928009 0 -0.6094809 -0.7928008 0 -0.6307268 -0.776005 0 -0.6265093 -0.7794138 4.27724e-4 -0.667788 -0.7443516 0 -0.7071068 -0.7071068 0 -0.7443516 -0.667788 0 -0.7720621 -0.6355471 0 -0.7720621 -0.6355471 0 -0.7443516 -0.667788 0 -0.7071068 -0.7071068 0 -0.667788 -0.7443516 0 -0.6307269 -0.776005 0 -0.667788 -0.7443515 0 -0.7071068 -0.7071068 0 -0.7443515 -0.667788 0 -0.7720621 -0.6355471 0 -0.8121884 -0.5833953 0 -0.8425822 -0.5385679 0 -0.8705036 -0.492162 0 -0.8958725 -0.4443113 0 -0.918613 -0.3951582 0 -0.938659 -0.3448467 0 -0.9559525 -0.2935216 0 -0.9704409 -0.2413387 0 -0.9820836 -0.1884456 0 -0.9908457 -0.1349992 0 -0.9967012 -0.08115851 0 -0.9996333 -0.0270797 0 -0.9996333 0.0270797 0 -0.9967012 0.08115851 0 -0.9908457 0.1349992 0 -0.9820836 0.1884456 0 -0.9704409 0.2413387 0 -0.9559525 0.2935216 0 -0.938659 0.3448467 0 -0.918613 0.3951582 0 -0.8958725 0.4443113 0 -0.8705036 0.492162 0 -0.8425822 0.5385679 0 -0.8121884 0.5833953 0 -0.7889903 0.6144056 0 -0.7443515 0.667788 0 -0.7071068 0.7071068 0 -0.667788 0.7443515 0 -0.6307268 0.776005 0 -0.667788 0.7443516 0 -0.7071068 0.7071068 0 -0.7443516 0.667788 0 -0.7720621 0.6355471 0 -0.5833953 0.8121884 0 -0.5385679 0.8425822 0 -0.492162 0.8705036 0 -0.4443113 0.8958724 0 -0.3951582 0.9186131 0 -0.3448467 0.938659 0 -0.2935216 0.9559525 0 -0.2413387 0.9704409 0 -0.1884456 0.9820836 0 -0.1349992 0.9908457 0 -0.08115851 0.9967013 0 -0.0270797 0.9996333 0 0.0270797 0.9996333 0 0.08115851 0.9967013 0 0.1349992 0.9908457 0 0.1884456 0.9820836 0 0.2413387 0.9704409 0 0.2935216 0.9559525 0 0.3448467 0.938659 0 0.3951582 0.9186131 0 0.4443113 0.8958724 0 0.492162 0.8705036 0 0.5385679 0.8425822 0 0.5833953 0.8121884 0 0.6265094 0.7794139 0 0.667788 0.7443515 0 0.7071068 0.7071068 0 0.7443515 0.667788 0 0.7794139 0.6265094 0 0.8121884 0.5833953 0 0.8425822 0.5385679 0 0.8705036 0.492162 0 0.8958724 0.4443113 0 0.9186131 0.3951582 0 0.938659 0.3448467 0 0.9559525 0.2935216 0 0.9704409 0.2413387 0 0.9820836 0.1884456 0 0.9908457 0.1349992 0 0.9967013 0.08115851 0 0.9996333 0.0270797 0 0.9996333 -0.0270797 0 0.9967013 -0.08115851 0 0.9908457 -0.1349992 0 0.9820836 -0.1884456 0 0.9704409 -0.2413387 0 0.9559525 -0.2935216 0 0.938659 -0.3448467 0 0.9186131 -0.3951582 0 0.8958724 -0.4443113 0 0.8705036 -0.492162 0 0.8425822 -0.5385679 0 0.8121884 -0.5833953 0 0.7794139 -0.6265094 0 0.7443515 -0.667788 0 0.7071068 -0.7071068 0 0.667788 -0.7443515 0 0.6265094 -0.7794139 0 0.5833953 -0.8121884 0 0.5385679 -0.8425822 0 0.492162 -0.8705036 0 0.4443113 -0.8958724 0 0.3951582 -0.9186131 0 0.3448467 -0.938659 0 0.2935216 -0.9559525 0 0.2413387 -0.9704409 0 0.1884456 -0.9820836 0 0.1349992 -0.9908457 0 0.08115851 -0.9967013 0 0.0270797 -0.9996333 0 -0.0270797 -0.9996333 0 -0.08115851 -0.9967013 0 -0.1349992 -0.9908457 0 -0.1884456 -0.9820836 0 -0.2413387 -0.9704409 0 -0.2935216 -0.9559525 0 -0.3448467 -0.938659 0 -0.3951582 -0.9186131 0 -0.4443113 -0.8958724 0 -0.492162 -0.8705036 0 -0.5385679 -0.8425822 0 -0.5833953 -0.8121884 0 0 1 0 0 1 0 0 -1 0 0 -1 0 1 0 0 1 0 0 0 1 0 0 1 0 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 -1 0 0 -1 0 1 0 0 1 0 0 0 -1 0 0 -1 0 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 1 0 0 1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 1 0 0 1 0 0 0 0 -1 0 0 -1 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 1 0 0 1 0 0 1 0 0 1 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -0.9659259 0.258819 0 -0.9659259 0.258819 0 0 1 0 0 1 0 -1 0 0 -1 0 0 -0.9659259 0.2588189 0 -0.9659258 0.2588189 0 -0.5 0.8660254 0 -0.5 0.8660254 0 -0.9659258 -0.2588189 0 -0.9659259 -0.258819 0 0 -1 0 0 -1 0 -1 0 0 -1 0 0 -0.9659259 -0.2588189 0 -0.9659258 -0.2588189 0 -0.5 -0.8660253 0 -0.5 -0.8660253 0 -0.1840623 -0.3188052 0.9297764 -0.1840623 -0.3188053 0.9297765 -0.1846225 -0.317127 0.9302393 -0.1840661 -0.318812 0.9297734 -0.1840623 -0.3188052 0.9297764 -0.1840809 -0.3188375 0.9297617 -0.1840622 -0.3188052 0.9297764 -0.1840623 -0.3188053 0.9297765 -0.184063 -0.3188048 0.9297765 0.5 0.8660254 0 0.5 0.8660254 0 0.8660255 -0.5 0 0.8660397 -0.4999753 0 0.8660254 -0.5 0 -0.5 -0.8660254 0 -0.5 -0.8660254 0 -0.8660255 0.4999999 0 -0.8660254 0.4999999 0 -0.8660397 0.4999753 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 -0.1840623 -0.3188053 0.9297764 -0.1840622 -0.3188052 0.9297765 0.4226182 -0.9063078 0 0.4226182 -0.9063078 1.46573e-7 0.4226184 -0.9063078 0 -0.1840623 0.3188052 0.9297765 -0.1840628 0.3188049 0.9297765 -0.1840623 0.3188052 0.9297764 -0.1840758 0.3188287 0.9297658 -0.1840623 0.3188053 0.9297765 -0.1840623 0.3188053 0.9297765 -0.183993 0.3190203 0.9297164 -0.1840639 0.3188081 0.9297752 -0.1840623 0.3188052 0.9297764 0.5 -0.8660255 0 0.5 -0.8660255 0 0.8660254 0.5 0 0.8660255 0.5 0 0.8660397 0.4999753 0 -0.5 0.8660254 0 -0.5 0.8660254 0 -0.8660254 -0.4999999 3.71471e-7 -0.8660848 -0.499897 0 -0.8660255 -0.4999999 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 -0.1840622 0.3188052 0.9297765 -0.1840623 0.3188052 0.9297765 0.4226182 0.9063078 1.46573e-7 0.4226184 0.9063078 0 0.4226182 0.9063078 0 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0.5938168 -0.8046003 0 0.7579729 -0.6522861 0 0.8841161 -0.4672675 0 0.9659262 -0.2588178 0 0.9992967 -0.03739225 -0.002794206 0.9993007 0.03739088 0 0.9825664 0.1859116 0 0.916562 0.3998925 0 0.8045956 0.5938231 0 0.6522889 0.7579705 0 0.4672719 0.8841137 0 0.2588171 0.9659264 0 0.03739249 0.9993006 0 -0.1859116 0.9825664 0 -0.3998925 0.916562 0 -0.5938218 0.8045966 0 -0.7579705 0.6522889 0 -0.8841148 0.4672696 0 -0.9659266 0.2588164 0 -0.9993006 0.03739261 0 -0.9825664 -0.1859116 0 -0.916562 -0.3998925 0 -0.8045989 -0.5938186 0 -0.6522874 -0.7579717 0 -0.4672675 -0.8841161 0 -0.2588171 -0.9659264 0 -0.03739249 -0.9993006 0 0.1859116 -0.9825664 0 0.3998925 -0.916562 0 0.3998925 -0.916562 0 0.1859116 -0.9825664 0 -0.03739249 -0.9993006 0 -0.2588171 -0.9659264 0 -0.4672675 -0.8841161 0 -0.6522874 -0.7579717 0 -0.8045989 -0.5938186 0 -0.916562 -0.3998925 0 -0.9825664 -0.1859116 0 -0.9993006 0.03739261 0 -0.9659266 0.2588164 0 -0.8841148 0.4672696 0 -0.7579705 0.6522889 0 -0.5938218 0.8045966 0 -0.3998925 0.916562 0 -0.1859116 0.9825664 0 0.03739249 0.9993006 0 0.2588171 0.9659264 0 0.4672719 0.8841137 0 0.6522889 0.7579705 0 0.8045956 0.5938231 0 0.916562 0.3998925 0 0.9825664 0.1859116 0 0.9972037 -0.07473152 0 0.9659262 -0.2588178 0 0.8841161 -0.4672675 0 0.7579729 -0.6522861 0 0.5938168 -0.8046003 0 0.6045979 -0.7965309 0 0.7836948 -0.6211462 0 0.9135438 -0.4067405 0 0.9859963 -0.1667676 0 0.9945221 0.1045271 0 0.9964914 0.0836755 -0.001824259 0.9443747 0.3288714 0 0.832923 0.5533888 0 0.6691299 0.7431456 0 0.4632962 0.8862034 0 0.2283529 0.9735785 0 -0.02094632 0.9997807 0 -0.2689186 0.9631629 0 -0.4446359 0.8957115 0 -0.4999952 0.866022 0.003285348 -0.6996628 0.7144731 0 -0.8553657 0.5180248 0 -0.957318 0.2890368 0 -0.9991229 0.04187434 0 -0.9781476 -0.2079112 0 -0.8957104 -0.444638 0 -0.7569957 -0.6534199 0 -0.5707129 -0.8211497 0 -0.3485752 -0.9372809 0 -0.1045247 -0.9945222 0 0.1460831 -0.9892722 0 0.3875159 -0.9218631 0 0.3875159 -0.9218631 0 0.1460831 -0.9892722 0 -0.1045247 -0.9945222 0 -0.3485752 -0.9372809 0 -0.5707129 -0.8211497 0 -0.7569957 -0.6534199 0 -0.8957104 -0.444638 0 -0.9781476 -0.2079112 0 -0.9991229 0.04187434 0 -0.957318 0.2890368 0 -0.8553657 0.5180248 0 -0.6996628 0.7144731 0 -0.5533872 0.8329241 0 -0.2689186 0.9631629 0 -0.02094632 0.9997807 0 0.2283529 0.9735785 0 0.4632962 0.8862034 0 0.6691299 0.7431456 0 0.832923 0.5533888 0 0.9443747 0.3288714 0 0.9997805 -0.02094715 0 0.9859963 -0.1667676 0 0.9135438 -0.4067405 0 0.7836948 -0.6211462 0 0.6045979 -0.7965309 0 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0.3998925 0.916562 0 0.1859116 0.9825664 0 -0.03739249 0.9993006 0 -0.2588171 0.9659264 0 -0.4672675 0.8841161 0 -0.6522874 0.7579717 0 -0.8045989 0.5938186 0 -0.916562 0.3998925 0 -0.9825664 0.1859116 0 -0.9993006 -0.03739261 0 -0.9659266 -0.2588164 0 -0.8841148 -0.4672696 0 -0.7579705 -0.6522889 0 -0.5938218 -0.8045966 0 -0.3998925 -0.916562 0 -0.1859116 -0.9825664 0 0.03739249 -0.9993006 0 0.2588171 -0.9659264 0 0.4672719 -0.8841137 0 0.6522889 -0.7579705 0 0.8045956 -0.5938231 0 0.916562 -0.3998925 0 0.9825664 -0.1859116 0 0.9972037 0.07473152 0 0.9992967 0.03739225 -0.002794206 0.9659262 0.2588178 0 0.8841161 0.4672675 0 0.7579729 0.6522861 0 0.5938168 0.8046003 0 0.5938168 0.8046003 0 0.7579729 0.6522861 0 0.8841161 0.4672675 0 0.9659262 0.2588178 0 0.9993007 -0.03739088 0 0.9825664 -0.1859116 0 0.916562 -0.3998925 0 0.8045956 -0.5938231 0 0.6522889 -0.7579705 0 0.4672719 -0.8841137 0 0.2588171 -0.9659264 0 0.03739249 -0.9993006 0 -0.1859116 -0.9825664 0 -0.3998925 -0.916562 0 -0.5938218 -0.8045966 0 -0.7579705 -0.6522889 0 -0.8841148 -0.4672696 0 -0.9659266 -0.2588164 0 -0.9993006 -0.03739261 0 -0.9825664 0.1859116 0 -0.916562 0.3998925 0 -0.8045989 0.5938186 0 -0.6522874 0.7579717 0 -0.4672675 0.8841161 0 -0.2588171 0.9659264 0 -0.03739249 0.9993006 0 0.1859116 0.9825664 0 0.3998925 0.916562 0 0.387517 0.9218626 0 0.1460827 0.9892724 0 -0.1045308 0.9945217 0 -0.3485708 0.9372825 0 -0.5707129 0.8211497 0 -0.7569968 0.6534186 0 -0.8957116 0.4446356 0 -0.9781475 0.2079125 0 -0.9991229 -0.04187434 0 -0.9573189 -0.289034 0 -0.8553646 -0.5180265 0 -0.6996629 -0.7144733 0 -0.4999997 -0.8660194 0.003285586 -0.5533957 -0.8329185 0 -0.2689186 -0.9631629 0 -0.02094024 -0.9997808 0 0.2283464 -0.9735799 0 0.4632975 -0.8862029 0 0.6691317 -0.7431439 0 0.8329197 -0.5533938 0 0.9443765 -0.328866 0 0.9964914 -0.0836755 -0.001824259 0.9997805 0.02094715 0 0.9859963 0.1667676 0 0.9135459 0.4067357 0 0.7836925 0.6211491 0 0.6046003 0.796529 0 0.6046003 0.796529 0 0.7836925 0.6211491 0 0.9135459 0.4067357 0 0.9859963 0.1667676 0 0.9945221 -0.1045271 0 0.9443765 -0.328866 0 0.8329197 -0.5533938 0 0.6691317 -0.7431439 0 0.4632975 -0.8862029 0 0.2283464 -0.9735799 0 -0.02094024 -0.9997808 0 -0.2689186 -0.9631629 0 -0.4446359 -0.8957115 0 -0.6996629 -0.7144733 0 -0.8553646 -0.5180265 0 -0.9573189 -0.289034 0 -0.9991229 -0.04187434 0 -0.9781475 0.2079125 0 -0.8957116 0.4446356 0 -0.7569968 0.6534186 0 -0.5707129 0.8211497 0 -0.3485708 0.9372825 0 -0.1045308 0.9945217 0 0.1460827 0.9892724 0 0.387517 0.9218626 0 0.6427876 0.7660443 0 0.6427877 0.7660444 0 0.6427877 0.7660444 0 0.6427878 -0.7660444 0 0.6427876 -0.7660443 -2.51693e-7 0.6427876 -0.7660444 0 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0.3681246 0 0.9297764 0.3681247 0 0.9297766 0.3681247 0 0.9297766 0.3681246 0 0.9297764 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 0 1 0 0 1 0 0 -1 0 0 -1 0 1 0 0 1 0 0 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 -0.9921142 -0.1253373 0 -0.9297772 -0.3681228 0 -0.8090184 -0.5877833 0 -0.6374225 -0.7705146 0 -0.4257787 -0.9048273 0 -0.1873819 -0.9822871 0 0.06279057 -0.9980267 0 0.3090171 -0.9510565 0 0.5358275 -0.8443275 0 0.7289696 -0.6845461 0 0.8763064 -0.4817542 0 0.9685831 -0.24869 0 0.9980264 0.06279391 0 0.9980264 -0.06279414 0 0.9980264 -0.06279414 0 0.9685831 0.24869 0 0.8763064 0.4817542 0 0.7289692 0.6845465 0 0.5358285 0.8443269 0 0.3090158 0.951057 0 0.06279057 0.9980267 0 -0.1873812 0.9822874 0 -0.4257793 0.904827 0 -0.6374225 0.7705146 0 -0.8090182 0.5877836 0 -0.9297772 0.3681228 0 -0.9921141 0.1253371 0 -0.9921141 0.1253371 0 -0.9297772 0.3681228 0 -0.8090182 0.5877836 0 -0.6374225 0.7705146 0 -0.4257793 0.904827 0 -0.1873812 0.9822874 0 0.06279057 0.9980267 0 0.3090158 0.951057 0 0.5358285 0.8443269 0 0.7289692 0.6845465 0 0.8763064 0.4817542 0 0.9685831 0.24869 0 0.9980264 0.06279391 0 0.9685831 -0.24869 0 0.8763064 -0.4817542 0 0.7289696 -0.6845461 0 0.5358275 -0.8443275 0 0.3090171 -0.9510565 0 0.06279057 -0.9980267 0 -0.1873819 -0.9822871 0 -0.4257787 -0.9048273 0 -0.6374225 -0.7705146 0 -0.8090184 -0.5877833 0 -0.9297772 -0.3681228 0 -0.9921142 -0.1253373 0 -0.9937118 -0.1119673 0 -0.9438829 -0.3302803 0 -0.8467279 -0.5320262 0 -0.7071039 -0.7071097 0 -0.5320327 -0.8467239 0 -0.3302798 -0.9438831 0 -0.1119642 -0.9937123 0 0.1119642 -0.9937123 0 0.3302798 -0.9438831 0 0.5320327 -0.8467239 0 0.7071067 -0.7071069 0 0.8467229 -0.5320343 0 0.9438829 -0.3302803 0 0.9937126 -0.1119617 0 0.9937126 0.1119617 0 0.9438829 0.3302803 0 0.8467229 0.5320343 0 0.7071067 0.7071069 0 0.5320327 0.8467239 0 0.3302798 0.9438831 0 0.1119642 0.9937123 0 -0.1119642 0.9937123 0 -0.3302798 0.9438831 0 -0.5320327 0.8467239 0 -0.7071039 0.7071097 0 -0.8467279 0.5320262 0 -0.9438829 0.3302803 0 -0.9937118 0.1119673 0 -0.9937118 0.1119673 0 -0.9438829 0.3302803 0 -0.8467279 0.5320262 0 -0.7071039 0.7071097 0 -0.5320327 0.8467239 0 -0.3302798 0.9438831 0 -0.1119642 0.9937123 0 0.1119642 0.9937123 0 0.3302798 0.9438831 0 0.5320327 0.8467239 0 0.7071067 0.7071069 0 0.8467229 0.5320343 0 0.9438829 0.3302803 0 0.9937126 0.1119617 0 0.9937126 -0.1119617 0 0.9438829 -0.3302803 0 0.8467229 -0.5320343 0 0.7071067 -0.7071069 0 0.5320327 -0.8467239 0 0.3302798 -0.9438831 0 0.1119642 -0.9937123 0 -0.1119642 -0.9937123 0 -0.3302798 -0.9438831 0 -0.5320327 -0.8467239 0 -0.7071039 -0.7071097 0 -0.8467279 -0.5320262 0 -0.9438829 -0.3302803 0 -0.9937118 -0.1119673 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 0 0 -1 0 0 -1 -1 0 0 -1 0 0 0 1 0 0 1 0 0 0 1 0 0 1 0 -1 0 0 -1 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 0 0 -1 0 0 -1 0 0 1 0 0 1 -1 0 0 -1 0 0 -1 0 0 -1 0 0 0 0 1 0 0 1 0 0 -1 0 0 -1 1 0 0 1 0 0 0.7071068 0 0.7071068 0.7071068 0 0.7071068 0 0 1 0 0 1 -0.7071048 0 0.7071087 -0.7071048 0 0.7071087 -0.9961947 0 0.08715522 -0.9961947 0 0.08715522 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 -1 0 0 -1 0 0 -0.1959457 0 0.9806147 -0.1959457 0 0.9806147 -0.1959458 0 -0.9806147 -0.1959453 4.34817e-7 -0.9806149 -0.195946 2.39408e-6 -0.9806146 -0.1959465 6.28852e-7 -0.9806146 -0.1959475 5.88133e-7 -0.9806144 -0.1959447 1.25579e-6 -0.980615 -0.1959462 -1.91787e-6 -0.9806147 -0.1959478 2.13058e-5 -0.9806144 -0.1959453 -4.34817e-7 -0.9806149 -0.1959496 -1.06659e-6 -0.980614 -0.1959449 1.34512e-6 -0.9806149 -0.195945 2.26594e-6 -0.9806149 -0.1959453 3.4922e-6 -0.9806148 -0.1959456 -2.56083e-6 -0.9806148 -0.1959462 1.89196e-6 -0.9806147 -0.1959447 -1.2558e-6 -0.9806149 -0.1959465 -6.18546e-7 -0.9806147 -0.195946 -7.031e-7 -0.9806147 -0.195946 -2.39408e-6 -0.9806146 -0.1959462 1.86119e-6 -0.9806147 -0.1959465 6.13246e-7 -0.9806146 -0.1959496 1.06659e-6 -0.980614 -0.1959465 -6.13243e-7 -0.9806146 -0.1959478 -2.13058e-5 -0.9806144 -0.195945 -2.16153e-6 -0.980615 -0.1959456 0 -0.9806148 -0.195945 2.1505e-6 -0.980615 -0.1959453 -3.4922e-6 -0.9806148 -0.1959449 -1.34999e-6 -0.980615 -0.1959475 -6.21643e-7 -0.9806144 -0.195946 7.031e-7 -0.9806147 -0.1959501 1.0238e-6 -0.9806138 -0.1959452 3.91866e-7 -0.9806148 -0.1959456 2.56083e-6 -0.9806148 -0.1959475 6.21643e-7 -0.9806144 -0.1959452 -3.91866e-7 -0.9806148 -0.1959475 -5.88133e-7 -0.9806144 -0.1959462 -1.86119e-6 -0.9806147 -0.195945 -2.26594e-6 -0.9806149 -0.1959501 -1.02505e-6 -0.9806138 0.9768825 -0.08716118 -0.1952007 0.9472022 -0.2588146 -0.18927 0.8887372 -0.4226213 -0.1775875 0.8032731 -0.5735757 -0.1605101 0.6933997 -0.7071063 -0.1385552 0.5624582 -0.8191515 -0.1123904 0.4144241 -0.9063084 -0.08281028 0.2538009 -0.9659261 -0.05071449 0.0854671 -0.9961945 -0.01707798 -0.0854671 -0.9961946 0.01707798 -0.2538009 -0.9659261 0.05071425 -0.4144242 -0.9063085 0.08281028 -0.5624584 -0.8191514 0.1123905 -0.6933997 -0.7071063 0.1385552 -0.8032729 -0.573576 0.16051 -0.8887372 -0.4226213 0.1775875 -0.9472022 -0.2588142 0.18927 -0.9768825 -0.08716118 0.1952007 -0.9768825 0.08716118 0.1952007 -0.9472022 0.2588142 0.18927 -0.8887372 0.4226213 0.1775875 -0.8032743 0.5735739 0.1605103 -0.6933977 0.7071084 0.1385542 -0.5624585 0.8191514 0.1123901 -0.4144242 0.9063085 0.08281028 -0.2538009 0.9659261 0.05071425 -0.0854671 0.9961946 0.01707798 0.0854671 0.9961945 -0.01707798 0.253801 0.9659261 -0.05071431 0.4144243 0.9063085 -0.08280998 0.5624582 0.8191515 -0.1123904 0.6933977 0.7071084 -0.1385542 0.8032744 0.5735736 -0.1605103 0.8887374 0.4226213 -0.1775869 0.9472023 0.2588146 -0.1892693 0.9768825 0.08716118 -0.1952007 0.9768834 0.08715265 -0.1952002 0.9472001 0.2588226 -0.1892696 0.8887405 0.4226143 -0.1775882 0.8032706 0.5735794 -0.1605089 0.6934018 0.7071042 -0.1385556 0.5624545 0.8191542 -0.1123893 0.4144274 0.906307 -0.08281093 0.2537988 0.9659267 -0.05071407 0.08546704 0.9961946 -0.01707792 -0.0854671 0.9961946 0.01707798 -0.2538009 0.9659261 0.05071431 -0.4144275 0.906307 0.08281058 -0.5624545 0.8191542 0.1123897 -0.6934018 0.7071042 0.1385556 -0.8032706 0.5735794 0.1605089 -0.8887407 0.4226143 0.1775875 -0.9472002 0.2588226 0.1892688 -0.9768834 0.08715265 0.1952002 -0.9768834 -0.08715265 0.1952002 -0.9472002 -0.2588226 0.1892688 -0.8887407 -0.4226143 0.1775875 -0.8032692 -0.5735815 0.1605087 -0.693404 -0.707102 0.1385555 -0.5624545 -0.8191541 0.1123892 -0.4144275 -0.906307 0.08281058 -0.2538009 -0.9659261 0.05071431 -0.0854671 -0.9961946 0.01707798 0.08546704 -0.9961946 -0.01707792 0.2537989 -0.9659267 -0.05071389 0.4144275 -0.9063069 -0.08281058 0.5624545 -0.8191542 -0.1123893 0.693404 -0.707102 -0.1385555 0.8032692 -0.5735814 -0.1605086 0.8887405 -0.4226143 -0.1775875 0.9472002 -0.2588226 -0.1892688 0.9768834 -0.08715265 -0.1952002 -0.1959462 -6.65179e-7 -0.9806147 -0.1959459 -1.26253e-6 -0.9806147 -0.195946 -1.65058e-6 -0.9806146 -0.1959456 -2.62672e-6 -0.9806148 -0.1959479 5.85841e-6 -0.9806143 -0.1959461 -3.39274e-7 -0.9806147 -0.1959459 2.57205e-6 -0.9806147 -0.1959459 -1.39119e-6 -0.9806147 -0.1959455 -9.06197e-7 -0.9806148 -0.1959462 3.47654e-7 -0.9806147 -0.1959491 4.56494e-6 -0.9806141 -0.195946 3.10003e-6 -0.9806147 -0.195944 -1.66066e-5 -0.980615 -0.1959456 9.45398e-7 -0.9806148 -0.1959463 -1.14578e-6 -0.9806147 -0.1959473 4.07774e-6 -0.9806144 -0.1959395 -1.25393e-5 -0.980616 -0.1959465 -1.03167e-6 -0.9806146 -0.1959456 1.2547e-6 -0.9806147 -0.1959462 -1.80556e-7 -0.9806147 -0.1959462 1.41941e-7 -0.9806147 -0.1959459 3.18332e-7 -0.9806147 -0.1959453 -1.32478e-6 -0.9806149 -0.1959457 3.97341e-7 -0.9806148 -0.1959461 -3.39274e-7 -0.9806146 -0.1959463 -1.72508e-6 -0.9806146 -0.1959457 1.04115e-6 -0.9806149 -0.195946 -6.6204e-7 -0.9806147 -0.1959459 3.18332e-7 -0.9806148 -0.1959459 4.57736e-7 -0.9806147 -0.1959458 4.80991e-7 -0.9806147 -0.1959462 -6.81773e-7 -0.9806146 -0.1959459 0 -0.9806147 -0.1959473 -1.627e-6 -0.9806144 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 0 0 -1 0 0 -1 0 1 0 0 1 0 0 0 1 0 0 1 0 -1 0 0 -1 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 0 -0.1361667 -0.9906859 0 -0.3983988 -0.9172124 0 -0.63109 -0.7757095 0 -0.8169681 -0.5766829 0 -0.942262 -0.3348767 0 -0.9976687 -0.06824392 0 -0.9790834 0.2034592 0 -0.8878881 0.4600596 0 -0.7308331 0.6825563 0 -0.519585 0.8544188 0 -0.2697983 0.962917 0 0.06823945 0.997669 0 -0.06823849 0.997669 0 -0.06823849 0.997669 0 0.2697964 0.9629174 0 0.519585 0.8544188 0 0.7308366 0.6825525 0 0.8878853 0.4600651 0 0.9790834 0.2034592 0 0.9976687 -0.06824392 0 0.9422598 -0.334883 0 0.8169681 -0.5766829 0 0.6310935 -0.7757068 0 0.3983988 -0.9172124 0 0.1361667 -0.9906859 0 0.1361667 -0.9906859 0 0.3983988 -0.9172124 0 0.6310935 -0.7757068 0 0.8169681 -0.5766829 0 0.9422598 -0.334883 0 0.9976687 -0.06824392 0 0.9790834 0.2034592 0 0.8878853 0.4600651 0 0.7308366 0.6825525 0 0.519585 0.8544188 0 0.2697964 0.9629174 0 0.06823945 0.997669 0 -0.2697983 0.962917 0 -0.519585 0.8544188 0 -0.7308331 0.6825563 0 -0.8878881 0.4600596 0 -0.9790834 0.2034592 0 -0.9976687 -0.06824392 0 -0.942262 -0.3348767 0 -0.8169681 -0.5766829 0 -0.63109 -0.7757095 0 -0.3983988 -0.9172124 0 -0.1361667 -0.9906859 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 0 -0.9635489 0.2675321 0 -0.8835134 0.4684059 0 -0.7621622 0.6473862 0 -0.6051731 0.7960939 0 -0.4198893 0.9075753 0 -0.2149724 0.9766201 0 0.05413591 0.9985336 0 -0.05413591 0.9985336 0 -0.05413591 0.9985336 0 0.2149724 0.9766201 0 0.4198893 0.9075753 0 0.6051731 0.7960939 0 0.7621622 0.6473862 0 0.8835134 0.4684059 0 0.9635489 0.2675321 0.009215116 -0.9784741 -0.2061635 -0.002303481 -0.9965097 -0.08344477 0.01109957 -0.9117048 -0.4106959 0 -0.9476507 -0.319309 0.01374787 -0.8025928 -0.5963689 0 -0.8568581 -0.5155523 0.01745343 -0.6558582 -0.7546823 0 -0.7259965 -0.6876984 0.02248489 -0.4775685 -0.8783069 0 -0.561185 -0.8276905 0.02867454 -0.2748087 -0.9610713 0 -0.37014 -0.9289761 0.01761239 -0.1080993 -0.9939842 0 -0.1617792 -0.986827 0 0.05413591 -0.9985335 0.01761239 0.1080993 -0.9939842 0 0.3193054 -0.9476519 0.02867454 0.2748087 -0.9610713 0 0.5155523 -0.8568581 0.02248489 0.4775685 -0.8783069 0 0.6877001 -0.725995 0.01745343 0.6558582 -0.7546823 0 0.8276891 -0.5611869 0.01374787 0.8025928 -0.5963689 0 0.9289759 -0.37014 0.01109957 0.9117048 -0.4106959 0 0.9868271 -0.1617779 0.00921601 0.9784743 -0.2061626 -0.01402467 0.9976406 -0.06720578 0 0.9967014 0.08115601 0 0.9985337 0.05413395 0.01179152 0.9998134 -0.0153039 -0.007071077 0.9780573 -0.208216 0.001767516 0.9965552 -0.0829125 -0.008129119 0.9106202 -0.4131643 0 0.9476507 -0.3193091 -0.009464859 0.800594 -0.5991324 0 0.8568581 -0.5155523 -0.01108533 0.6527994 -0.7574497 0 0.7259966 -0.6876984 -0.01292192 0.4737071 -0.8805876 0 0.5611849 -0.8276905 -0.01475191 0.2713064 -0.96238 0 0.37014 -0.9289759 -0.0081622 0.1081125 -0.9941052 0 0.1617792 -0.986827 0 -0.05413591 -0.9985336 -0.0081622 -0.1081125 -0.9941052 0 -0.3193054 -0.9476519 -0.01475191 -0.2713064 -0.96238 0 -0.5155522 -0.8568581 -0.01292192 -0.4737071 -0.8805876 0 -0.6877 -0.7259949 -0.01108533 -0.6527994 -0.7574497 0 -0.8276892 -0.5611869 -0.009464859 -0.800594 -0.5991324 0 -0.928976 -0.37014 -0.008129119 -0.9106202 -0.4131643 0 -0.9868263 -0.1617832 -0.007070362 -0.9780572 -0.2082167 0.01765853 -0.9978201 -0.06358724 0.001753091 -0.9985318 0.05413925 -0.01402467 -0.9976406 -0.06720578 0 -0.9967014 0.08115601 -0.002283811 -0.9985309 0.05413919 0.001768231 -0.9965552 -0.08291321 0 -0.9476507 -0.3193091 0 -0.8568581 -0.5155523 0 -0.7259966 -0.6876984 0 -0.5611849 -0.8276905 0 -0.37014 -0.9289759 0 -0.1617792 -0.986827 0 0.05413591 -0.9985336 0 0.3193054 -0.9476519 0 0.5155522 -0.8568581 0 0.6877 -0.7259949 0 0.8276892 -0.5611869 0 0.928976 -0.37014 0 0.9868272 -0.1617779 0.001752376 0.9985322 0.05413383 0 0.994139 -0.1081099 0 0.9476507 -0.319309 0 0.8568581 -0.5155523 0 0.7259965 -0.6876984 0 0.561185 -0.8276905 0 0.37014 -0.9289761 0 0.1617792 -0.986827 0 -0.05413591 -0.9985335 0 -0.3193054 -0.9476519 0 -0.5155523 -0.8568581 0 -0.6877001 -0.725995 0 -0.8276891 -0.5611869 0 -0.9289759 -0.37014 0 -0.9868263 -0.1617832 0 0.9635489 0.2675321 0 0.8835134 0.4684059 0 0.7621622 0.6473862 0 0.6051731 0.7960939 0 0.4198893 0.9075753 0 0.2149724 0.9766201 0 0.05413591 0.9985336 0 -0.2149724 0.9766201 0 -0.4198893 0.9075753 0 -0.6051731 0.7960939 0 -0.7621622 0.6473862 0 -0.8835134 0.4684059 0 -0.9635489 0.2675321 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -0.3152948 -0.9489833 -0.004463374 -0.214973 -0.97662 0 -0.5119786 -0.8589846 -0.004853188 -0.4198815 -0.9075789 0 -0.6848984 -0.7286194 -0.005274236 -0.6051803 -0.7960885 0 -0.825872 -0.5638288 -0.005702018 -0.7621675 -0.64738 0 -0.9281251 -0.3722187 -0.00609523 -0.8835127 -0.4684071 0 -0.9866387 -0.1627975 -0.006400227 -0.9635483 -0.2675349 0 -0.9985336 0.05413591 0 -0.9985336 -0.05413591 0 -0.9985336 -0.05413591 0 -0.9766201 0.2149724 0 -0.9866387 0.1627975 -0.006400227 -0.9075774 0.4198848 0 -0.9281251 0.3722187 -0.00609523 -0.796094 0.6051732 0 -0.825872 0.5638288 -0.005702018 -0.6473863 0.7621622 0 -0.6848984 0.7286194 -0.005274236 -0.4684036 0.8835146 0 -0.5119786 0.8589846 -0.004853188 -0.2675336 0.9635486 0 -0.3152948 0.9489833 -0.004463374 -0.02711147 0.9981641 -0.05416136 -0.05413395 0.9985337 0 -0.07910954 0.9968639 -0.002060472 0.2108771 0.9775032 -0.004285573 0.1081099 0.994139 0 0.4160492 0.9093302 -0.0046525 0.3193091 0.9476506 0 0.6019593 0.7985107 -0.005062282 0.5155427 0.8568639 0 0.7598395 0.6500874 -0.005489766 0.6877037 0.7259914 0 0.8821895 0.4708577 -0.005904793 0.8276955 0.5611774 0 0.9630798 0.2691431 -0.006260633 0.9289798 0.3701307 0 0.9984933 0.05448627 -0.006503105 0.986827 0.1617792 0 0.9941383 -0.108116 0 0.9984933 -0.05448627 -0.006503105 0.9476535 -0.3193005 0 0.9630798 -0.2691431 -0.006260633 0.8568558 -0.5155563 0 0.8821895 -0.4708577 -0.005904793 0.725995 -0.6877001 0 0.7598395 -0.6500874 -0.005489766 0.5611844 -0.8276908 0 0.6019593 -0.7985107 -0.005062282 0.3701419 -0.9289752 0 0.4160492 -0.9093302 -0.0046525 0.1617824 -0.9868265 0 0.2108775 -0.9775031 -0.004285156 -0.07910996 -0.9968639 -0.002060055 0 -0.9999994 0.001069188 0 -0.9967015 -0.08115434 -0.05413937 -0.9985334 0 0.08222204 -0.9966135 0.001072347 0.3193091 -0.9476506 0 0.5155427 -0.8568639 0 0.6877037 -0.7259914 0 0.8276955 -0.5611774 0 0.9289798 -0.3701307 0 0.986827 -0.1617792 0 0.9941383 0.108116 0 0.9476535 0.3193005 0 0.8568558 0.5155563 0 0.725995 0.6877001 0 0.5611844 0.8276908 0 0.3701419 0.9289752 0 0.1617771 0.9868273 0 -0.02703827 0.9996344 0 -0.214973 0.97662 0 -0.4198815 0.9075789 0 -0.6051803 0.7960885 0 -0.7621675 0.64738 0 -0.8835127 0.4684071 0 -0.9635483 0.2675349 0 -0.9985336 0.05413591 0 -0.9766201 -0.2149724 0 -0.9075774 -0.4198848 0 -0.796094 -0.6051732 0 -0.6473863 -0.7621622 0 -0.4684036 -0.8835146 0 -0.2675336 -0.9635486 0 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0.5 -0.8660255 0 0.5 -0.8660255 0 0.9775362 -0.2107679 0 0.9826828 -0.1852959 0 0.9871658 -0.1596989 0 0.9871658 -0.1596989 0 0.9826828 -0.1852959 0 0.9775362 -0.2107679 0 0.1613828 0.9868919 0 0.1863015 0.9824926 0 0.2111015 0.9774641 0 0.2111015 0.9774641 0 0.1863015 0.9824926 0 0.1613828 0.9868919 0 -0.5000001 0.8660255 0 -0.5000001 0.8660255 0 -0.9520596 0.305913 0 -0.9440145 0.3299039 0 -0.9353647 0.3536846 0 -0.9353647 0.3536846 0 -0.9440145 0.3299039 0 -0.9520596 0.305913 0 -0.3552795 -0.9347602 0 -0.3308706 -0.9436762 0 -0.3062376 -0.9519551 0 -0.3062376 -0.9519551 0 -0.3308706 -0.9436762 0 -0.3552795 -0.9347602 0 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 -1 0 0 -1 0 0 -0.6712985 -0.7411872 0 -0.6518121 -0.7583804 0 -0.6318864 -0.775061 0 -0.6318864 -0.775061 0 -0.6518121 -0.7583804 0 -0.6712985 -0.7411872 0 0.7739828 -0.6332067 0 0.7577122 -0.652589 0 0.7409582 -0.671551 0 0.7409582 -0.671551 0 0.7577122 -0.652589 0 0.7739828 -0.6332067 0 1 0 0 1 0 0 0.7409582 0.671551 0 0.7577122 0.652589 0 0.7739828 0.6332067 0 0.7739828 0.6332067 0 0.7577122 0.652589 0 0.7409582 0.671551 0 -0.6318864 0.775061 0 -0.6518121 0.7583804 0 -0.6712985 0.7411872 0 -0.6712985 0.7411872 0 -0.6518121 0.7583804 0 -0.6318864 0.775061 0 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0.5 0.8660255 0 0.5 0.8660255 0 -0.3062376 0.9519551 0 -0.3308706 0.9436762 0 -0.3552795 0.9347602 0 -0.3552795 0.9347602 0 -0.3308706 0.9436762 0 -0.3062376 0.9519551 0 -0.9353647 -0.3536846 0 -0.9440145 -0.3299039 0 -0.9520596 -0.305913 0 -0.9520596 -0.305913 0 -0.9440145 -0.3299039 0 -0.9353647 -0.3536846 0 -0.5000001 -0.8660255 0 -0.5000001 -0.8660255 0 0.2111015 -0.9774641 0 0.1863015 -0.9824926 0 0.1613828 -0.9868919 0 0.1613828 -0.9868919 0 0.1863015 -0.9824926 0 0.2111015 -0.9774641 0 0.9871658 0.1596989 0 0.9826828 0.1852959 0 0.9775362 0.2107679 0 0.9775362 0.2107679 0 0.9826828 0.1852959 0 0.9871658 0.1596989 0 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 1 0 0 1 0 0 0 0 1 0 0 1 0 1 0 0 1 0 -1 0 0 -1 0 0 0 -1 0 0 -1 0 1 0 0 1 0 0 0 0 1 0 0 1 0 1 0 0 1 0 -1 0 0 -1 0 0 0 -1 0 0 -1 0 1 0 0 1 0 0 0 0 1 0 0 1 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 1 0 0 1 0 0 1 0 0 1 0 -1 0 0 -1 0 0 0 0 1 0 0 1 -1 0 0 -1 0 0 0 0.9986295 0.05233651 0 0.9986295 0.05233544 0 0.9986296 0.05233544 0 0.9986295 0.05233615 0 0.9986295 0.05233615 0 0.9986296 0.05233597 0 0.9986295 0.05233603 0 0.9986296 0.0523352 0 0.9986295 0.05233651 0 0.9986296 0.0523352 0 0.9986295 0.05233651 0 0.9986296 0.05233567 0 0.9986296 0.05233621 0 0.9986296 0.05233573 0 0.9986295 0.05233651 0 0.9986301 0.05232483 0 0.9986301 0.05232429 0 0.9986295 0.05233627 0.8247538 0.5644236 0.03474426 0.9160195 0.3996261 0.03474444 0.9747388 0.2206285 0.03474444 0.9988249 0.03378874 0.03474414 0.9874209 -0.154249 0.03474426 0.9409314 -0.3368099 0.03474432 0.8610109 -0.5073983 0.0347442 0.7504974 -0.6599593 0.03474438 0.6133173 -0.789072 0.03474444 0.4543434 -0.8901489 0.03474438 0.2792294 -0.9595956 0.03474432 0.0941925 -0.9949476 0.03474432 -0.09419202 -0.9949476 0.03474432 -0.2792282 -0.959596 0.03474432 -0.4543446 -0.8901482 0.03474432 -0.6133173 -0.789072 0.03474426 -0.7504974 -0.6599593 0.03474426 -0.8610106 -0.5073989 0.0347442 -0.9409323 -0.3368074 0.0347442 -0.9874209 -0.154249 0.03474414 -0.9988248 0.0337916 0.03474426 -0.974739 0.2206275 0.03474438 -0.9160195 0.3996261 0.0347442 -0.8247538 0.5644236 0.0347442 0.6004871 0.7988878 0.03454977 0.6121795 0.7899535 0.03477841 0.5908026 0.8060904 0.03421396 0.5831346 0.8116732 0.03377521 0.5773795 0.8157995 0.03322935 0.5735113 0.81855 0.03256916 0.5715619 0.819943 0.03178805 0.7041836 0.7091671 0.03474915 0.7041099 0.7092405 0.0347439 -0.7041792 0.7091717 0.03474426 -0.7048083 0.7087221 0.03095626 -0.6261178 0.7789471 0.03489768 -0.612199 0.7899385 0.03477859 -0.6004736 0.7988979 0.03454929 -0.5908159 0.8060806 0.03421437 -0.5831372 0.8116713 0.03377509 -0.5773743 0.8158031 0.03322845 -0.5735164 0.8185463 0.03257006 -0.5715619 0.8199431 0.03178691 -0.7041814 0.7091695 0.03474438 0.7048183 0.7087322 0.03049248 0.6266369 0.7785295 0.03490191 -0.8247542 0.564423 0.03474426 -0.9160197 0.3996258 0.0347442 -0.97474 0.2206234 0.0347442 -0.9988249 0.03378874 0.03474444 -0.9874204 -0.1542518 0.03474426 -0.9409329 -0.3368058 0.03474414 -0.8610109 -0.5073983 0.0347442 -0.7504963 -0.6599607 0.0347442 -0.6133169 -0.7890723 0.03474426 -0.4543452 -0.8901479 0.03474426 -0.2792283 -0.9595959 0.03474432 -0.0941925 -0.9949476 0.03474432 0.09419202 -0.9949476 0.03474432 0.2792297 -0.9595955 0.03474432 0.4543446 -0.8901482 0.03474432 0.6133169 -0.7890723 0.03474438 0.7504963 -0.6599607 0.03474444 0.8610126 -0.5073955 0.03474438 0.9409323 -0.3368074 0.0347442 0.9874212 -0.1542472 0.03474438 0.998825 0.03378629 0.03474426 0.9747402 0.2206231 0.0347442 0.9160197 0.3996258 0.03474444 0.824752 0.5644261 0.03474438 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 + + + + + + + + + + + + + + + 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 +

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

+ + + + + + + + + 0.001 0 0 0 0 0.001 0 0 0 0 0.001 0 0 0 0 1 + + + + + + + + + + + + + + diff --git a/kuka_kr16_support/meshes/kr16_2/visual/link_1.dae b/kuka_kr16_support/meshes/kr16_2/visual/link_1.dae new file mode 100644 index 000000000..31c136871 --- /dev/null +++ b/kuka_kr16_support/meshes/kr16_2/visual/link_1.dae @@ -0,0 +1,311 @@ + + + + + Blender User + Blender 2.79.0 commit date:2017-09-11, commit time:10:43, hash:5bd8ac9abfa + + 2017-11-10T20:33:31 + 2017-11-10T20:33:31 + + 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.512 0.2088141 0.07027201 1 + + + 0.015625 0.015625 0.015625 1 + + + 1 + + + 1 + + + + + + + + + + + 0 0 0 1 + + + 0 0 0 1 + + + 0.00200704 0.00200704 0.00200704 1 + + + 0.03125 0.03125 0.03125 1 + + + 10 + + + 1 + + + + + + + + + + + + + + + + + + + 166.3059 -46.91076 800 187 -56.12435 800 189.3678 -54.40402 800 181.4634 -57.9233 800 184.3262 -57.31479 800 178.5366 -57.9233 800 170.6322 -54.40402 800 173 -56.12435 800 167.2104 -49.69431 800 168.6738 -52.22899 800 178.5366 -30.07669 800 173 -31.87565 800 170.6322 -33.59597 800 168.6738 -35.77101 800 187 -31.87565 800 184.3262 -30.68521 800 166.3059 -41.08924 800 166 -44 800 167.2104 -38.30569 800 175.6738 -30.68521 800 181.4634 -30.07669 800 192.7896 -38.30569 800 191.3262 -35.77101 800 193.6941 -46.91076 800 194 -44 800 191.3262 -52.22899 800 192.7896 -49.69431 800 189.3678 -33.59597 800 175.6738 -57.31479 800 193.6941 -41.08924 800 179.0244 -57.99586 785.4196 181.9653 -57.89079 786.854 184.8108 -57.17854 788.2419 187.4463 -55.89001 789.5272 189.756 -54.08166 790.6539 191.6396 -51.83213 791.5725 193.0136 -49.24095 792.2428 193.6941 -46.91076 792.5744 193.9999 -44.73295 792.7235 193.82 -41.58231 792.6359 193.0136 -38.75905 792.2429 191.6396 -36.16788 791.5726 189.756 -33.91828 790.6539 187.4462 -32.10998 789.5273 184.8109 -30.8215 788.242 181.9653 -30.1092 786.8541 179.0243 -30.00415 785.4196 176.7809 -30.31969 784.2799 173.4238 -31.60783 779.9724 170.9908 -33.2461 776.8583 168.9517 -35.35448 774.2483 167.3958 -37.84006 772.257 166.3903 -40.59611 770.9702 165.9495 -43.99996 770.4061 166.3903 -47.40387 770.97 167.3958 -50.15991 772.2568 168.9517 -52.64556 774.2484 170.9909 -54.75393 776.8585 173.4237 -56.39213 779.9724 176.7658 -57.67568 784.2736 176.8497 38.13343 784.3585 169.4168 41.60679 774.8436 160.798 46.11613 763.812 147.1694 54.43297 746.3682 133.5943 64.27389 728.993 176.8473 -70.58002 784.3562 153.7426 50.23615 754.7815 141.4401 58.36122 739.035 168.859 -72.28308 774.1298 125.982 70.62006 719.2498 164.2708 -73.41258 768.2572 133.0346 -84.33988 728.2765 158.0746 -75.12815 760.3264 118.8351 75 710.102 150.3303 -77.56729 750.414 141.0528 -80.97535 738.5393 121.1662 75 713.0857 123.8597 -88.72299 716.5332 118.7927 -91.39065 710.0421 121.1753 74.99685 710.102 118.8345 78.64952 710.1016 98.40168 103.07 605.3361 92.66463 108.2567 605.9459 92.66463 108.2567 671.7438 98.40034 103.1073 680.1511 104.0295 97.38645 604.7753 104.7024 96.66199 689.3877 109.0714 91.70204 604.119 109.8934 90.75352 696.996 114.0232 85.46907 603.4336 115.4951 83.46678 705.2065 118.5752 79.03044 602.8664 121.1944 74.98604 602.2816 97.57094 107.2825 605.8394 97.54187 107.2874 678.8923 92.67597 111.5162 590.5958 118.8763 83.02156 581.9342 121.1662 79.64766 580.585 115.5673 87.57337 583.5985 112.5695 91.3975 584.8266 108.5626 96.1521 586.2209 104.1433 100.8891 587.8363 98.20922 106.7055 589.2685 128.1007 68.80363 601.7976 134.7986 63.32563 601.2925 142.3681 57.70172 600.7255 147.059 54.55733 600.302 254.8701 21.01391 787.3916 253.4945 21.03538 808 260 21.00225 808 260 21.00225 787.5 248.0484 21.22531 786.8746 244.2388 21.44659 808 240.8364 21.71558 785.8671 234.2556 22.38348 808 233.6038 22.46199 784.3685 225.0564 23.69105 781.9509 225.3096 23.66107 807.9963 217.7109 25.06152 779.2589 215.2476 25.57131 803.0867 206.7185 27.64116 798.9268 210.3483 26.70933 775.968 203.8359 28.42948 772.4765 199.7676 29.62821 795.5365 193.1105 31.75756 792.2897 197.0558 30.44744 768.2715 190.4687 32.68765 763.4448 183.9382 35.14541 787.8161 186.0453 34.3292 759.7717 181.8962 35.97699 755.9725 177.0914 38.02725 751.037 171.6558 40.52585 744.66 167.4685 42.58888 738.9818 163.6923 44.54639 733.2022 159.0945 47.0823 724.7751 155.9862 48.87969 717.9248 153.8518 50.16521 712.3099 151.7455 51.46204 705.6724 150.9092 52.00546 600.0054 150.6787 52.13819 648.334 148.8535 53.31175 657.5244 147.9956 53.87351 664.2372 147.4979 54.20218 672.6817 147.6846 54.0776 681.8003 148.5361 53.51833 690.3576 150.125 52.49207 699.159 152.9794 50.69908 640.2344 159.6524 46.7629 624.0742 155.5799 49.12689 633.0968 158.6891 47.32294 599.5955 163.095 44.87042 617.8423 166.9336 42.87292 599.1137 167.2193 42.70951 611.349 172.2337 40.25205 604.6208 175.1527 38.89645 598.6644 177.4323 37.87435 598.5773 260 -44 808 225.3214 -44 808 336.5195 14 592.5317 336.5195 21.90193 592.5317 331.7986 22.78772 588.3644 330.1426 14 587.044 325.124 23.87662 583.2415 323.3735 14 582.0482 319.8536 24.62013 579.7435 316.25 14 577.5722 314.4346 25.30443 576.5243 308.8119 14 573.641 308.8119 25.91726 573.641 303.0649 26.46855 571.0474 301.1009 14 570.2767 297.1564 26.94346 568.8131 293.16 14 567.4981 291.1517 27.35465 566.8787 285.0336 14 565.3206 282.9862 27.78515 564.8534 276.7673 14 563.7565 276.7673 28.01827 563.7565 270.5053 28.18509 562.9718 268.4071 14 562.8146 260.0026 28.28607 562.4724 260 14 562.5 254.5826 28.27787 562.6314 251.5929 14 562.8146 243.2327 14 563.7565 249.1024 28.35771 563.0084 234.9664 14 565.3206 236.5612 28.91574 564.9541 242.858 28.57405 563.81 226.84 14 567.4981 231.6882 29.26795 566.1222 218.8991 14 570.2767 226.0353 29.77041 567.7452 221.172 30.28164 569.4128 211.1881 14 573.641 215.7337 30.92663 571.5489 203.75 14 577.5722 209.6227 31.77828 574.402 196.6265 14 582.0482 201.7843 33.02258 578.7335 189.8574 14 587.044 190.1125 35.19398 586.8414 195.7799 34.09206 582.6232 183.4806 14 592.5317 185.6176 36.11105 590.6002 177.5317 14 598.4806 181.912 36.89174 594.0043 172.044 14 604.8574 167.0481 14 611.6265 162.5721 14 618.75 158.641 14 626.1881 155.2767 14 633.8991 152.4981 14 641.84 150.3206 14 649.9664 148.7565 14 658.2327 147.8146 14 666.5928 147.5 14 675 147.8146 14 683.4072 148.7565 14 691.7673 150.3206 14 700.0336 152.4981 14 708.16 155.2767 14 716.1009 158.641 14 723.812 162.5721 14 731.25 167.0481 14 738.3735 172.044 14 745.1426 177.5317 14 751.5194 183.4806 14 757.4683 189.8574 14 762.9561 196.6265 14 767.9519 203.75 14 772.4279 211.1881 14 776.359 218.8991 14 779.7233 226.84 14 782.502 234.9664 14 784.6794 243.2327 14 786.2435 251.5929 14 787.1854 260 14 787.5 268.4071 21 787.1854 276.7673 21 786.2435 276.7673 14 786.2435 285.0336 21 784.6794 285.0336 14 784.6794 293.16 14 782.502 293.16 21 782.502 301.1009 21 779.7233 301.1009 14 779.7233 308.8119 14 776.359 316.25 14 772.4279 308.8119 21 776.359 316.25 21 772.4279 323.3735 21 767.9519 330.1426 21 762.9561 330.1426 14 762.9561 336.5195 14 757.4683 336.5195 21 757.4683 342.4683 21 751.5194 342.4683 14 751.5194 347.9561 14 745.1426 347.9561 21 745.1426 352.9519 21 738.3735 352.9519 14 738.3735 357.4279 14 731.25 357.4279 21 731.25 361.359 21 723.812 361.359 14 723.812 364.7233 14 716.1009 367.502 14 708.16 364.7233 21 716.1009 367.502 21 708.16 369.6794 21 700.0336 369.6794 14 700.0336 371.2435 21 691.7673 371.2435 14 691.7673 372.1854 21 683.4072 372.1854 14 683.4072 372.5 14 675 372.5 21 675 372.1854 21 666.5928 372.1854 14 666.5928 371.2435 21 658.2327 371.2435 14 658.2327 369.6794 21 649.9664 369.6794 14 649.9664 367.502 21 641.84 367.502 14 641.84 364.7233 21 633.8991 364.7233 14 633.8991 361.359 21 626.1881 357.4279 21 618.75 357.4279 14 618.75 361.359 14 626.1881 352.9519 21 611.6265 352.9519 14 611.6265 347.9561 21 604.8574 347.9561 14 604.8574 341.1713 20.98546 597.059 342.4683 14 598.4806 323.3735 14 767.9519 268.4071 14 787.1854 259.9989 32.77376 541.2811 248.3587 32.57991 543.2974 239.7408 32.87909 544.7903 229.822 33.68839 546.5084 220.3178 34.95571 548.1547 212.3497 36.40221 549.5349 205.7248 37.84902 550.6826 195.7684 40.52059 552.4073 185.6519 43.8285 554.1597 175.019 48.01277 556.0015 168.9194 50.76173 557.0551 160.7453 56.2493 551.8594 152.2016 62.5451 546.4292 143.1164 69.89292 540.655 137.343 75.00105 536.9863 129.2141 74.99996 568.1015 124.1238 75.00035 589.366 392.69 21 684.0762 393 21 675 385.3207 21 719.539 388.068 21 710.883 390.2182 21 702.0596 368.657 21 751.6985 373.6378 21 744.1047 391.7612 21 693.1102 329.1047 21 788.6378 336.6985 21 783.657 343.9347 21 778.1696 378.0888 21 736.1887 381.9891 21 727.9874 393 21 600.1 278.1102 21 806.7612 287.0597 21 805.2182 350.7796 21 772.2012 357.2012 21 765.7796 363.1696 21 758.9347 389.6749 21 596.7749 295.883 21 803.068 312.9873 21 796.9891 321.1887 21 793.0888 304.539 21 800.3207 269.0762 21 807.69 393 -67 600.1 393 -67 675 168.9237 -46.48676 557.0573 271.9799 -46.48676 539.2056 271.9799 33.23672 539.2056 133.1166 -46.48676 534.2993 133.1166 75 534.2993 284.3568 -46.48676 513.829 284.3568 38.63069 513.829 266.8684 -46.48676 496.625 266.8684 42.28752 496.625 260 48.56554 467.1 260 43.40842 491.3624 169.8189 -46.48676 422.2652 147.3253 -46.48676 413.9911 138.1073 -46.48676 421.2263 195.4129 64.13853 441.8755 201.6683 61.14706 446.6685 209.7122 57.59365 452.8316 187.3356 68.33635 435.6868 226.1788 51.48237 465.4484 217.8636 54.39028 459.0773 175.9303 74.99877 426.9476 236.4062 48.41185 473.2846 246.6846 45.87475 481.1602 254.7899 44.273 487.3704 169.8189 75 422.2652 138.1073 75 421.2263 147.3253 75 413.9911 251.134 50.55041 458.2345 240.7833 53.3805 447.8835 230.4786 56.74795 437.5786 223.1877 59.47983 430.2877 218.0128 61.58122 425.1128 212.816 63.83886 419.916 207.6442 66.23358 414.7442 203.0229 68.493 410.1235 196.295 70.59525 410.1235 188.9685 73.18226 410.1235 184.2551 75.00151 410.1239 133.9842 75 410.1235 133.9842 75 424.491 137.9632 75 424.491 128.3109 237.5819 410.1235 128.3072 237.5652 421.6534 137.951 59.96471 424.7522 137.9345 57.55948 425.1166 137.9353 75 425.1235 124.0968 74.99995 426.6975 129.1707 74.99938 425.1235 76.59423 128.2631 425.1235 110.7333 100.2284 425.1235 116.4186 93.56826 425.1235 121.6182 86.69063 425.1235 126.4082 79.55625 425.1235 86.04424 122.0785 425.1235 93.33889 116.6122 425.1235 103.2179 108.0022 425.1235 60.15864 136.6737 425.1228 66.42063 133.779 425.1235 131.2645 74.92662 424.4926 122.7035 89.44801 424.2386 112.1574 103.3541 423.9961 100.023 115.888 423.7774 87.96547 125.907 423.6025 77.19437 133.1147 423.4768 68.6263 137.989 423.3914 60.15863 142.1159 423.3194 95.74332 252.4544 421.3935 83.4346 256.7853 421.3179 107.8284 247.5339 421.4794 70.93099 260.5164 421.2528 119.6617 242.0353 421.5754 60.15869 263.2127 421.2058 60.15542 263.2294 410.1235 60.15877 180.7889 410.1239 -15.67624 189.9682 410.1235 -15.82125 144.1027 426.7121 -0.3459355 190.5497 410.1235 -1.205236 144.9974 426.6968 -8.299982 144.7622 426.7023 7.631403 144.8006 426.7009 15.49449 189.9922 410.1236 15.79864 144.1362 426.7026 23.94465 143.0039 426.7037 37.46083 186.8791 410.1235 51.82945 183.3658 410.1235 31.64535 141.5046 426.7023 121.7314 78.7811 426.7023 117.2979 85.23016 426.7018 112.3776 91.62921 426.7014 107.0047 97.85196 426.702 101.2406 103.7789 426.7067 95.508 109.0865 426.7065 89.3217 114.2219 426.7023 83.32538 118.6609 426.7025 76.12664 123.4089 426.7003 69.19542 127.4236 426.7025 62.0015 131.0762 426.7012 54.46267 134.3852 426.7017 47.11339 137.1325 426.7023 39.58043 139.4803 426.7128 -30.53849 188.0944 410.1235 -21.39676 143.4126 426.7023 -21.37682 143.4183 426.8865 -58.26173 263.6391 410.1235 -70.93099 260.5164 410.1235 -19.5574 269.2908 410.1235 -32.5449 268.0314 410.1235 45.4564 266.146 410.1235 -45.4564 266.146 410.1235 -6.524211 269.9212 410.1235 19.5574 269.2908 410.1235 6.524211 269.9212 410.1235 32.5449 268.0314 410.1235 -92.78182 196.4796 410.1235 -83.4346 256.7853 410.1235 -94.74958 252.829 410.1235 -94.75045 252.8405 421.125 -91.64014 163.7861 422.6794 -107.8284 247.5339 421.2176 -119.6617 242.0353 421.3136 -146.148 227.0679 421.5749 -131.2155 235.9714 421.4194 -148.0818 171.7487 422.5404 193.2117 -188.5981 410.1235 159.2441 -84.72482 410.1235 167.6822 -82.49685 410.1235 202.0979 -179.0431 410.1235 182.6752 -79.47568 410.1235 133.3126 -94.23207 410.1235 174.1074 -206.3652 410.1235 183.8743 -197.7125 410.1235 153.3775 -222.2056 410.1235 163.9339 -214.536 410.1235 176.4096 -80.58335 410.1235 189.3458 -78.50766 410.1235 203.0236 -77.24805 410.1235 269.6847 -13.04461 410.1235 254.6942 -89.61512 410.1235 258.7264 -77.20533 410.1235 244.8561 113.7783 410.1235 239.0731 125.4753 410.1235 225.8469 147.9634 410.1235 183.8743 197.7125 410.1235 174.1074 206.3652 410.1235 128.3135 -237.5939 410.1235 142.4629 -229.3563 410.1235 142.713 -90.30815 410.1235 197.0387 -77.68588 410.1235 210.5121 -169.07 410.1235 264.97 51.87421 410.1235 262.1543 64.61523 410.1235 268.7395 26.05876 410.1235 267.1667 39.01204 410.1235 270 0 410.1235 262.1543 -64.61523 410.1235 250.0671 101.8156 410.1235 218.4346 158.702 410.1235 153.3775 222.2056 410.1235 142.4629 229.3563 410.1235 193.2117 188.5981 410.1235 202.0979 179.0431 410.1235 150.8409 -87.35245 410.1235 239.0731 -125.4753 410.1235 244.8561 -113.7783 410.1235 218.4346 -158.702 410.1235 225.8469 -147.9634 410.1235 269.6847 13.04461 410.1235 264.97 -51.87421 410.1235 250.0671 -101.8156 410.1235 232.7318 136.8792 410.1235 210.5121 169.07 410.1235 163.9339 214.536 410.1235 137.2153 -92.53842 410.1235 232.7318 -136.8792 410.1235 258.7264 77.20533 410.1235 254.6942 89.61512 410.1235 267.1667 -39.01204 410.1235 268.7395 -26.05876 410.1235 128.3072 -237.5652 421.3916 133.4143 -92.72113 423.9214 210.7551 -76.12078 417.8547 297.3095 -66.99694 504.4094 -146.1516 227.0236 410.1235 -148.0825 171.7277 410.1235 -147.9502 175.5183 421.079 -195.6072 104.0661 410.1235 -190.1583 114.9071 410.1235 -232.7318 136.8792 410.1235 -244.7031 114.1069 410.1235 -200.3291 93.415 410.1236 -184.1951 125.4404 410.1235 -225.8469 147.9634 410.1235 -239.0731 125.4753 410.1235 -183.8743 197.7125 410.1235 -155.5424 163.9409 410.1235 -153.3775 222.2056 410.1235 -163.9339 214.536 410.1235 -177.7338 135.6375 410.1235 -218.4346 158.702 410.1235 -174.1074 206.3652 410.1235 -193.2117 188.5981 410.1235 -163.388 154.9139 410.1235 -170.7918 145.4709 410.1235 -210.5121 169.07 410.1235 -202.0979 179.0431 410.1235 -139.8677 38.30523 473.6046 -213.6599 57.38653 470.077 -214.9631 46.8462 474.2119 -137.9078 44.79338 470.9991 -211.7701 67.839 465.9456 -141.6691 30.9009 476.5552 -135.6814 51.19372 468.4137 -209.2989 78.1753 461.8287 -206.2529 88.3674 457.7377 -131.9986 60.05515 464.8031 -202.6405 98.38774 453.6834 -198.4713 108.2092 449.677 -128.6439 66.90113 461.9871 -124.967 73.57656 459.2201 -188.5093 127.1495 441.8508 -193.7566 117.8051 445.7292 -119.826 81.68219 455.8253 -114.1607 89.42927 452.5416 -176.475 144.9833 434.3439 -182.7436 136.2171 438.0523 -108.2714 96.46632 449.5202 -162.4985 161.5176 427.2375 -169.7205 153.4244 430.7358 -103.3412 101.7133 447.2392 -98.49065 106.4418 445.1626 -91.23226 112.7251 442.3609 -83.57577 118.5131 439.7295 -75.55255 123.7823 437.2793 -54.12841 134.5376 432.0157 -62.90872 130.6627 433.9673 -215.6762 36.24654 478.339 -215.779 22.81755 483.5261 -143.231 22.59341 479.8419 -45.10998 137.8236 430.2791 -35.89521 140.5055 428.7653 -68.93516 127.5655 435.4756 -154.8285 169.2408 423.8588 -28.45654 142.1802 427.7324 -219.1989 1.208057 416.9235 -219.1414 -2.353046 418.2947 -200.9385 93.69918 416.9235 -204.551 84.20343 416.9235 -208.3742 72.6187 416.9235 -211.6328 60.84798 416.9235 -214.318 48.92316 416.9235 -216.4225 36.87652 416.9235 -217.9406 24.74069 416.9235 -218.8682 12.54854 416.9235 -192.1422 -2.436233 416.9235 -144.2594 14.53409 458.9508 -150.0614 14.44989 458.9824 -150.0614 -1.743098 416.9235 -150.0614 -7.365689 467.3566 -145.0177 0.367285 464.3882 -144.8134 -7.365457 467.3566 -144.8241 7.139208 461.7887 -150.0614 -26.74492 458.7284 -144.2674 -14.80882 464.0428 -142.5378 -26.72868 458.7367 -214.6178 100.0779 413 -214.6178 100.0779 416.9235 -244.7065 114.1082 413 -232.1475 42.74094 416.9235 -232.1475 42.74094 413 -267.1667 39.01204 413 -247.9159 26.41226 413 -244.3183 27.97654 413 -241.0097 30.08434 413 -255.6188 25.05404 413 -251.7139 25.43004 413 -254.6942 89.61512 413 -258.7264 77.20533 413 -238.0716 32.68377 413 -259.5345 25.29353 413 -264.97 51.87421 413 -235.5763 35.71082 413 -233.5853 39.09095 413 -250.0671 101.8156 413 -263.3644 26.14261 413 -262.1543 64.61523 413 -268.5718 27.73466 413 -263.3644 26.14261 416.9235 -268.5898 27.73855 416.9235 -259.5345 25.29353 416.9235 -255.6188 25.05404 416.9235 -251.7139 25.43004 416.9235 -247.9159 26.41226 416.9235 -244.3183 27.97654 416.9235 -241.0097 30.08434 416.9235 -238.0716 32.68377 416.9235 -235.5763 35.71082 416.9235 -233.5853 39.09095 416.9235 -269.6847 13.04461 416.9235 -270.0212 -3.499234 416.9235 -150.0614 -3.5 416.9235 -270 -3.5 401.9235 -270 0 401.9235 -150.0614 -3.5 401.9235 -150.0614 0 401.9235 -150.0614 0 401.5 -270 0 401.5 -150.0575 -39.65018 401.4985 -150.0614 -39.64462 425.1235 -140.9254 -34.25265 439.1702 -139.7861 -39.64462 425.1235 -139.4751 -39.64462 425.1235 -137.872 -44.90359 425.1235 -139.7861 -39.64462 401.5 -149.5051 -39.64462 401.9924 -149.5051 -39.64462 401.5 -122.6414 -78.00995 401.5 -131.9049 -61.29824 401.5 -122.6414 -78.00995 425.1235 -131.9049 -61.29824 425.1235 -134.4805 -54.2216 425.1235 -134.5008 -54.1748 453.1235 -137.871 -44.90627 453.1235 -126.3032 -71.22148 425.1235 -121.3013 -79.44257 425.1235 -130.738 -62.71026 425.1235 -121.5274 -79.60092 425.1235 -121.5274 -79.60092 427.5 -121.3009 -79.44234 427.5 -109.7691 -96.39353 427.5 -115.7955 -87.27194 427.5 -108.893 -95.77201 427.5 -109.7691 -96.39353 426 -108.8745 -95.76715 426 -90.25971 -124.2558 425.3707 -103.261 -101.7948 425.8491 -96.30084 -108.4027 425.6751 -89.89363 -113.7723 425.5257 -177.4143 -96.54742 455 -131.9514 -64.71393 455 -195.1311 -71.24526 401.5 -154.9452 -128.6366 455 -109.4823 -96.80311 455 -109.4823 -96.80311 426 -90.25971 -124.2558 426 -154.9452 -128.6366 426 -134.332 -158.0754 426 -90.36566 -127.2898 426 -90.36566 -127.2898 425.3258 -134.332 -158.0754 425.3258 -155.232 -128.227 427.5 -166.9903 -111.4344 427.5 -166.9903 -111.4344 401.5 -155.232 -128.227 426 -223.6778 -151.1274 427.5 -211.9195 -167.92 427.5 -223.7212 -151.1499 401.5 -264.97 -51.87421 401.5 -262.1543 -64.61523 401.5 -258.7264 -77.20533 401.5 -254.6942 -89.61512 401.5 -244.8561 -113.7783 401.5 -239.0731 -125.4753 401.5 -267.1667 -39.01204 401.5 -250.0671 -101.8156 401.5 -268.7395 -26.05876 401.5 -269.6847 -13.04461 401.5 -232.7318 -136.8792 401.5 -221.1562 -154.8551 401.5 -221.1152 -154.8268 410.1235 -217.1147 -160.5167 410.1235 -211.9195 -167.92 401.5 -217.0817 -160.5476 401.5 -211.6051 -167.6999 401.5 -186.6896 -150.2539 426 -211.6206 -167.7113 410.1235 -186.6896 -150.2539 410.1235 -158.6991 -190.2285 410.1235 -158.6991 -190.2285 425.0971 -193.2117 -188.5981 410.1235 -183.8743 -197.7125 410.1235 -202.0979 -179.0431 410.1235 -174.1074 -206.3652 410.1235 -153.3775 -222.2056 410.1235 -147.7053 -182.5305 410.1235 -163.9339 -214.536 410.1235 -146.1516 -227.0236 410.1235 -146.148 -227.0679 421.5748 -147.7053 -182.5305 422.3522 -90.90586 -142.7592 423.0465 -90.90586 -142.7588 425.113 -89.89337 -113.7874 423.5522 -147.7053 -182.5303 425.107 390.2182 -67 702.0596 388.068 -67 710.883 350.3966 -67 697.8916 351.9782 -67 690.3485 391.7612 -67 693.1102 385.3207 -67 719.539 348.1975 -67 705.2782 392.69 -67 684.0762 352.9315 -67 682.7005 353.25 -67 675 381.9891 -67 727.9874 345.3959 -67 712.4581 378.0888 -67 736.1887 342.0109 -67 719.3821 368.657 -67 751.6985 363.1696 -67 758.9347 333.5874 -67 732.2753 336.6985 -67 783.657 311.0029 -67 753.0658 317.2753 -67 748.5874 338.0658 -67 623.9971 333.5874 -67 617.7247 350.3966 -67 652.1085 348.1975 -67 644.7218 351.9782 -67 659.6516 373.6378 -67 744.1047 338.0658 -67 726.0029 357.2012 -67 765.7796 328.6063 -67 738.1565 343.9347 -67 778.1696 323.1565 -67 743.6063 342.0109 -67 630.6179 345.3959 -67 637.5419 352.9315 -67 667.2995 350.7796 -67 772.2012 329.1047 -67 788.6378 287.0597 -67 805.2182 275.3485 -67 766.9782 282.8915 -67 765.3966 278.1102 -67 806.7612 269.0762 -67 807.69 267.7005 -67 767.9315 260 -67 808 260 -67 768.25 311.0029 -67 596.9342 304.3821 -67 592.9891 323.1565 -67 606.3937 317.2753 -67 601.4127 321.1887 -67 793.0888 304.3821 -67 757.0109 312.9873 -67 796.9891 297.4581 -67 760.3959 295.883 -67 803.068 328.6063 -67 611.8435 304.539 -67 800.3207 290.2782 -67 763.1975 275.3485 -67 583.0218 267.7005 -67 582.0685 290.2782 -67 586.8026 282.8915 -67 584.6035 297.4581 -67 589.6041 260 -67 581.75 225.3214 -67.00914 808 244.6515 -67.00405 766.9782 252.2995 -67.00203 767.9315 237.1085 -67.00603 765.3966 229.7218 -67.00798 763.1975 215.8764 -67.00579 757.1644 222.5419 -67.00988 760.3959 260 -83 768.25 252.2995 -83 767.9315 244.6515 -83 766.9782 237.1085 -83 765.3966 229.7218 -83 763.1975 222.5419 -83 760.3959 215.6179 -83 757.0109 208.9971 -83 753.0658 209.5904 -67.05571 753.4779 202.7247 -83 748.5874 203.9323 -67.27708 749.5272 196.8435 -83 743.6063 199.7753 -67.54382 746.1929 195.9018 -67.86671 742.7274 191.529 -68.32513 738.3115 191.3937 -83 738.1565 187.7547 -68.79827 733.958 186.4126 -83 732.2753 181.9342 -83 726.0029 184.4224 -69.27326 729.6558 177.9891 -83 719.3821 178.4875 -70.27188 720.2911 181.0884 -69.81087 724.7177 175.8802 -70.76523 715.28 174.6041 -83 712.4581 173.4576 -71.26048 709.7775 171.8025 -83 705.2782 169.6034 -83 697.8916 171.0855 -71.77138 703.1751 169.569 -72.11627 697.7548 168.0218 -83 690.3485 168.3389 -72.40351 692.262 167.0685 -83 682.7005 167.3136 -72.64982 685.4086 166.8263 -72.76881 679.0106 166.75 -83 675 166.7625 -72.78462 672.5286 167.0685 -83 667.2995 167.2296 -72.67031 665.3157 168.0218 -83 659.6516 169.6034 -83 652.1085 168.2773 -72.41817 658.0638 169.462 -72.14096 652.678 171.8025 -83 644.7218 170.9148 -71.8095 647.3792 174.6041 -83 637.5419 173.2009 -71.31413 640.8748 177.9891 -83 630.6179 175.5359 -70.83378 635.4432 181.9342 -83 623.9971 179.6351 -70.05838 627.6555 186.4126 -83 617.7247 184.0439 -69.3299 620.87 191.3937 -83 611.8435 187.3601 -68.85041 616.5302 191.335 -68.34806 611.8981 196.8435 -83 606.3937 195.7408 -67.88372 607.4254 202.7247 -83 601.4127 199.6331 -67.55466 603.9268 208.9971 -83 596.9342 203.8467 -67.28553 600.5489 207.8107 -67.11259 597.7224 215.6179 -83 592.9891 212.1902 -67.01385 594.9362 222.5419 -83 589.6041 216.6498 -67.01179 592.4389 229.7218 -83 586.8026 222.5419 -67.00988 589.6041 237.1085 -83 584.6035 229.7218 -67.00798 586.8026 244.6515 -83 583.0218 237.1085 -67.00603 584.6035 252.2995 -83 582.0685 244.6515 -67.00405 583.0218 260 -83 581.75 252.2995 -67.00203 582.0685 267.7005 -83 582.0685 275.3485 -83 583.0218 282.8915 -83 584.6035 290.2782 -83 586.8026 297.4581 -83 589.6041 304.3821 -83 592.9891 311.0029 -83 596.9342 317.2753 -83 601.4127 323.1565 -83 606.3937 328.6063 -83 611.8435 333.5874 -83 617.7247 338.0658 -83 623.9971 342.0109 -83 630.6179 345.3959 -83 637.5419 348.1975 -83 644.7218 350.3966 -83 652.1085 351.9782 -83 659.6516 352.9315 -83 667.2995 353.25 -83 675 352.9315 -83 682.7005 351.9782 -83 690.3485 350.3966 -83 697.8916 348.1975 -83 705.2782 345.3959 -83 712.4581 342.0109 -83 719.3821 338.0658 -83 726.0029 333.5874 -83 732.2753 328.6063 -83 738.1565 323.1565 -83 743.6063 317.2753 -83 748.5874 311.0029 -83 753.0658 304.3821 -83 757.0109 297.4581 -83 760.3959 290.2782 -83 763.1975 282.8915 -83 765.3966 275.3485 -83 766.9782 267.7005 -83 767.9315 182.2638 -69.62692 786.9995 189.6746 -68.5461 790.6139 198.0634 -67.6735 794.7055 224.5704 -44 807.6337 205.7279 -67.19596 798.4436 212.2486 -67.01777 801.624 224.5704 -66 807.6337 225.3214 -66 808 230.9373 -67.01419 504.3347 224.9452 -67.00923 515.6538 227.0661 -67.00868 515.1392 222.7652 -67.00981 515.5499 228.9561 -67.00818 514.048 220.7028 -67.01036 514.8361 218.9251 -67.01082 513.5702 217.5756 -67.01305 511.8542 230.4622 -67.00778 512.4685 231.8753 -67.00741 508.3857 231.6678 -67.00746 506.2132 231.4622 -67.00753 510.5287 231.6678 -107.8 506.2132 230.8567 -107.8 504.1871 231.8753 -107.8 508.3857 231.4622 -107.8 510.5287 230.4622 -107.8 512.4685 228.9561 -107.8 514.048 227.0661 -107.8 515.1392 224.9452 -107.8 515.6538 222.7652 -107.8 515.5499 220.7028 -107.8 514.8361 218.9251 -107.8 513.5702 217.576 -107.8 511.8547 213.1772 -67.00802 504.236 202.7684 -69.25788 486.2073 185.076 -107.8 455.563 193.94 -71.57662 470.916 184.6939 -74.45433 454.8641 198.3567 -107.8 447.8954 198.0706 -73.65807 447.4125 211.9624 -70.48207 471.4612 205.7921 -71.78453 460.7739 184.2409 -74.67553 453.4336 184.2648 -107.8 453.5369 184.0379 -74.90327 451.5645 184.0574 -107.8 451.3644 184.4835 -75.09064 449.1286 184.4704 -107.8 449.2214 185.4705 -107.8 447.2816 186.9765 -107.8 445.7021 186.9262 -75.09076 445.724 185.4605 -75.13896 447.2741 188.8666 -107.8 444.6109 190.9875 -107.8 444.0963 189.1202 -74.92615 444.5007 190.9385 -74.74121 444.1017 193.1674 -107.8 444.2002 192.7545 -74.53209 444.107 195.2298 -107.8 444.914 195.1309 -74.20539 444.847 197.0076 -107.8 446.1799 196.9445 -73.90498 446.1135 243.4171 -66 808 260 -58 808 243.4171 -58 808 244.0518 -58 826.1764 244.0518 -66 826.1764 245.0563 -58 830.8616 245.0563 -66 830.8616 248.2707 -58 834.3695 248.2707 -66 834.3695 252.6802 -58 836.0711 252.6802 -66 836.0711 267.3197 -58 836.0711 267.3197 -66 836.0711 271.7294 -58 834.3695 271.7294 -66 834.3695 274.9438 -58 830.8616 274.9438 -66 830.8616 269.0762 -58 807.69 275.9482 -58 826.1764 276.6193 -58 806.9576 276.6213 -65.99982 806.9745 275.9482 -66 826.1764 269.0762 -44 807.69 278.1102 -44 806.7612 287.0597 -44 805.2182 294.3038 -66 803.5 294.3038 -44 803.5 287.0597 -66 805.2182 295.7437 -44 803.5 295.7437 -66 803.5 264.285 -66 836.3187 255.715 -66 836.3187 247.1669 -66 835.7065 295.1645 -66 810.0604 294.1543 -66 816.5684 292.7175 -66 822.9957 289.7272 -66.00002 832.647 272.8331 -66 835.7065 238.6844 -66 834.4852 230.3108 -66 832.6612 226.9843 -66 821.8121 225.5218 -66 814.7664 228.9502 -66 828.7343 281.3156 -66 834.4852 225.3146 -44 813.5 294.6854 -44 813.5 295.1645 -44 810.0604 281.3156 -76 834.4852 272.8331 -76 835.7065 264.285 -76 836.3187 255.715 -76 836.3187 247.1669 -76 835.7065 238.6844 -76 834.4852 230.3108 -76 832.6612 289.6892 -76 832.6612 225.2993 -49 813.5025 294.7093 -48.99998 813.5083 231.4093 -76 835.4969 231.4093 -49 835.4969 228.9502 -49 828.7343 226.9843 -49 821.8121 292.7175 -49 822.9957 290.8603 -49 829.3144 288.0909 -48.99995 836.6588 287.9965 -76 836.8576 281.6104 -76 843.1706 279.2709 -76 844.1462 284.0449 -76 841.6099 238.7668 -76 843.3601 268.4188 -76 845.5993 260 -76 845.8953 241.7023 -76 844.4503 234.07 -76 839.7954 232.5577 -76 837.7612 286.2051 -76 839.4752 276.7961 -76 844.713 251.5812 -76 845.5993 236.173 -76 841.7802 276.7961 -49 844.713 279.2709 -49 844.1462 232.5577 -49 837.7612 234.07 -49 839.7954 281.6104 -49 843.1706 236.2927 -49 841.871 238.7668 -49 843.3601 284.162 -49 841.5158 286.2051 -49 839.4752 268.4188 -49 845.5993 242.0354 -49 844.53 251.5812 -49 845.5993 260 -49 845.8953 182.5 14 752.5 337.5 14 752.5 182.5 14 597.5 337.5 14 597.5 182.5 52 752.5 182.5 52 597.5 337.5 52 752.5 337.5 52 597.5 76.15946 -120.4896 647.5521 69.03039 -88.86946 637.1029 62.08184 -93.85881 626.9184 55.4564 134.0125 617.2131 55.49072 97.873 617.2537 68.41967 -125 636.2078 75.47859 -83.46232 646.5541 83.51506 -115.4717 658.3333 62.1961 93.77964 627.0858 69.03036 88.86949 637.1029 81.50459 -77.58853 655.3865 94.0677 -107.3139 673.8004 87.07505 -71.28053 663.5511 75.47863 83.46229 646.5542 87.07505 71.28051 663.5511 101.7237 -101.8492 685.0217 92.15829 -64.57418 671.0015 81.50457 77.58855 655.3864 105.7888 -99.13978 690.9799 92.15827 64.5742 671.0014 96.72634 -57.50644 677.6972 111.843 -95.35651 699.8538 96.72634 57.50644 677.6971 100.7533 -50.1173 683.5996 100.7533 50.11729 683.5994 104.2166 -42.44865 688.6755 107.0972 -34.54207 692.8977 104.2166 42.44858 688.6755 109.3791 -26.44224 696.2423 107.0972 34.54228 692.8977 91.7235 112.3412 670.3643 111.0497 -18.19171 698.691 55.47721 -133.9769 617.236 55.4766 -97.87487 617.2362 109.3792 26.44212 696.2423 84.51833 117.8406 659.8038 112.0985 -9.843135 700.2282 111.0497 18.19171 698.691 75.87092 123.5997 647.1292 112.0985 9.843135 700.2282 112.5524 2.3977e-7 700.8933 63.97979 -130.1586 629.7003 73.57637 -125.0074 643.7658 67.6534 128.2825 635.0846 60.62664 131.7172 624.7855 -1.943953 145.0179 565.5325 -1.875428 112.5237 565.5941 6.973385 112.3136 573.5618 7.471324 144.8362 574.0101 14.52884 144.2703 580.3647 22.24444 143.3123 587.3119 15.34786 111.4784 581.1021 31.52746 141.5595 595.6704 23.63597 110.0196 588.5648 38.09832 139.9054 601.5867 31.7889 107.9465 595.9058 45.6129 137.6674 608.353 39.76781 105.2687 603.09 48.56201 101.5311 611.0083 -11.4299 144.5596 556.9969 -11.39519 111.9406 557.0189 -30.18172 141.8446 548.2553 -26.44298 109.379 549.9987 -18.14619 111.0584 553.8676 -30.34995 -141.8149 548.1768 -20.29746 -143.5966 552.8644 -18.14619 -111.0584 553.8676 -21.24489 143.4643 552.4226 -26.4431 -109.3789 549.9986 -39.7063 139.4764 543.8139 -34.54315 107.0969 546.2215 -39.28017 -139.6095 544.0125 -34.54295 -107.097 546.2216 -48.84835 136.5434 539.5509 -42.44946 104.2163 542.5347 -48.43056 -136.7049 539.7457 -42.44953 -104.2162 542.5347 -55.94906 133.7711 536.2398 -62.14402 131.0281 533.3509 -50.11816 100.7529 538.9588 -57.36707 -133.202 535.5786 -66.05331 -129.1151 531.5281 -50.11816 -100.7529 538.9588 -68.93516 127.5655 530.1842 -57.50731 96.72586 535.5131 -74.82804 124.2216 527.4364 -64.57499 92.15776 532.2174 -73.91354 -124.7871 527.8628 -57.50731 -96.72586 535.5131 -64.57503 -92.15773 532.2174 -82.52049 -119.2649 523.8493 -81.24208 120.103 524.4454 -86.77416 116.1917 521.8658 -71.28134 87.07442 529.0902 -71.28134 -87.07441 529.0902 -94.27015 110.1971 518.3703 -90.23529 -113.5342 520.2519 -77.58934 81.50387 526.1488 -77.58932 -81.50389 526.1487 -97.61928 -107.2565 516.8086 -99.91851 105.0776 515.7365 -104.7307 100.3082 513.4925 -83.46302 75.47786 523.4098 -104.2329 -100.8265 513.7247 -111.2902 -92.98289 510.4337 -83.46305 -75.47782 523.4097 -111.1362 93.16122 510.5056 -88.87017 69.02954 520.8883 -88.87015 -69.02957 520.8883 -115.8644 87.18058 508.3008 -120.3012 80.98072 506.2318 -93.78025 62.19523 518.5988 -116.5842 -86.24578 507.9652 -93.78026 -62.19521 518.5988 -11.39956 -144.561 557.0175 -11.36387 -111.9738 557.042 -98.16588 55.01311 516.5537 -98.16588 -55.01311 516.5537 -122.626 -77.41902 505.1477 -125.3948 72.84509 503.8567 -127.128 -69.80137 503.0485 -128.6439 66.90113 502.3416 -102.0029 47.52264 514.7645 -131.6455 60.82531 500.9419 -130.738 -62.71026 501.3651 -102.0029 -47.52264 514.7645 -133.9953 -55.47926 499.8461 -135.38 51.98566 499.2005 -105.269 39.76702 513.2415 -105.2691 -39.76688 513.2414 -137.9078 44.79338 498.0218 -107.9468 31.7881 511.9928 -136.3109 -49.44031 498.7664 -107.9467 -31.78823 511.9928 -140.0891 37.48728 497.0046 -140.2015 -37.11865 496.9522 -137.8724 -44.90214 498.0382 -110.0198 23.63518 511.0262 -142.1741 28.58282 496.0324 -141.6447 -31.01264 496.2792 -110.0198 -23.63518 511.0262 -143.097 -23.52683 495.602 -143.7647 18.95253 495.2906 -111.4785 15.34711 510.3459 -111.4785 -15.34711 510.3459 -144.5085 11.92812 494.9438 -112.1854 8.407136 510.0163 -144.6975 -9.661019 494.8557 -144.0214 -16.81759 495.1709 -144.9539 4.317272 494.7361 -112.5 2.103097 509.8696 -144.9792 -2.456833 494.7243 -112.3154 -6.956023 509.9557 -1.686604 -145.0263 565.7643 -1.439096 -112.5207 565.9871 8.223773 -144.7968 574.6876 6.973257 -112.3136 573.5616 17.78391 -143.9358 583.2956 15.34786 -111.4784 581.1021 27.26851 -142.4436 591.8355 23.63596 -110.0196 588.5648 36.62967 -140.3283 600.2644 31.78903 -107.9465 595.9058 47.09737 -137.1887 609.6895 39.76768 -105.2688 603.0898 48.43027 -101.5896 610.8897 0 -112.5 409.0035 -8.407136 -112.1854 409.0035 8.407136 -112.1854 409.0035 16.76726 -111.2435 409.0035 25.03361 -109.6794 409.0035 33.15996 -107.5019 409.0035 41.10086 -104.7233 409.0035 48.81192 -101.359 409.0035 56.25 -97.42786 409.0035 63.3735 -92.95186 409.0035 70.1426 -87.95604 409.0035 76.51943 -82.46834 409.0035 82.46834 -76.51943 409.0035 87.95604 -70.1426 409.0035 92.95186 -63.3735 409.0035 97.42786 -56.25 409.0035 101.359 -48.81192 409.0035 104.7233 -41.10086 409.0035 107.5019 -33.15996 409.0035 109.6794 -25.03361 409.0035 111.2435 -16.76726 409.0035 112.1854 -8.407136 409.0035 112.5 0 409.0035 112.1854 8.407136 409.0035 111.2435 16.76726 409.0035 109.6794 25.03361 409.0035 107.5019 33.15996 409.0035 104.7233 41.10086 409.0035 101.359 48.81192 409.0035 97.42786 56.25 409.0035 92.95186 63.3735 409.0035 87.95604 70.1426 409.0035 82.46834 76.51943 409.0035 76.51943 82.46834 409.0035 70.1426 87.95604 409.0035 63.3735 92.95186 409.0035 48.81192 101.359 409.0035 56.25 97.42786 409.0035 41.10086 104.7233 409.0035 33.15996 107.5019 409.0035 25.03361 109.6794 409.0035 16.76726 111.2435 409.0035 8.407136 112.1854 409.0035 0 112.5 409.0035 -8.407136 112.1854 409.0035 -16.76726 111.2435 409.0035 -25.03361 109.6794 409.0035 -33.15996 107.5019 409.0035 -41.10086 104.7233 409.0035 -48.81192 101.359 409.0035 -56.25 97.42786 409.0035 -63.3735 92.95186 409.0035 -70.1426 87.95604 409.0035 -76.51943 82.46834 409.0035 -82.46834 76.51943 409.0035 -87.95604 70.1426 409.0035 -92.95186 63.3735 409.0035 -97.42786 56.25 409.0035 -101.359 48.81192 409.0035 -104.7233 41.10086 409.0035 -107.5019 33.15996 409.0035 -109.6794 25.03361 409.0035 -111.2435 16.76726 409.0035 -112.5 0 409.0035 -112.1854 8.407136 409.0035 -112.1854 -8.407136 409.0035 -111.2435 -16.76726 409.0035 -109.6794 -25.03361 409.0035 -107.5019 -33.15996 409.0035 -104.7233 -41.10086 409.0035 -101.359 -48.81192 409.0035 -97.42786 -56.25 409.0035 -92.95186 -63.3735 409.0035 -87.95604 -70.1426 409.0035 -82.46834 -76.51943 409.0035 -76.51943 -82.46834 409.0035 -70.1426 -87.95604 409.0035 -63.3735 -92.95186 409.0035 -56.25 -97.42786 409.0035 -48.81192 -101.359 409.0035 -41.10086 -104.7233 409.0035 -33.15996 -107.5019 409.0035 -25.03361 -109.6794 409.0035 -16.76726 -111.2435 409.0035 91.03199 -109.6974 506.4518 83.06848 -115.7833 506.9407 76.55416 -120.1894 507.169 68.52428 -124.9862 507.5493 73.48471 -125 507.4516 68.42423 -127.8502 480.327 85.59023 -122.525 425.0491 73.50852 -125.0017 479.5083 78.00656 -124.9999 452.5593 82.21038 -125 425.1671 73.48471 -125 423.3565 82.21071 -125 423.3565 85.86833 -122.3174 423.4028 125.1579 -96.52208 423.8535 133.3342 -92.62681 423.9214 128.7884 -94.74411 425.145 122.763 -97.72592 425.1601 133.3684 -92.63078 425.1263 117.8121 -100.3926 423.786 117.1484 -100.7697 425.1708 109.852 -105.0534 423.7045 111.2693 -104.1772 425.1656 103.7732 -108.9438 425.2741 102.1778 -110.0476 423.6174 97.7516 -113.1617 425.283 95.42787 -114.8444 423.5332 93.90147 -116.0163 425.2263 107.8284 -247.5339 421.2176 119.6617 -242.0353 421.3136 66.90065 -128.6441 423.2928 83.4346 -256.7853 421.0561 95.74332 -252.4544 421.1317 73.7704 -259.7267 421.0048 66.90065 -128.6441 410.1235 73.76804 -259.7427 410.1235 65.05474 -129.5874 410.1235 47.378 -137.0413 410.1235 56.33977 -133.607 410.1235 38.20866 -139.8753 410.1235 28.87194 -142.0965 410.1235 19.40874 -143.6952 410.1235 9.860506 -144.6643 410.1235 0.2690733 -144.9998 410.1235 -9.323536 -144.6999 410.1235 -18.8753 -143.7662 410.1235 -23.47622 -143.0869 423.0407 -28.34437 -142.2027 423.0562 -37.68927 -140.0161 423.0943 -46.86906 -137.2162 423.1432 -55.84352 -133.8152 423.2026 -65.66712 -129.2736 423.2819 -69.0885 -127.4825 410.1235 -65.68698 -129.268 410.1235 -73.02027 -125.2719 423.3517 -69.0885 -127.4825 423.3131 -81.1473 -120.167 423.4408 -23.47622 -143.0869 410.1235 -71.35581 -129.0701 410.1235 -71.35581 -129.0701 423.2854 -27.2336 -250.684 410.1235 -23.64642 -147.9607 417.001 -23.65186 -148.1166 422.953 -27.2336 -250.684 414.3111 -62.41215 -249.4555 410.1235 -62.41215 -249.4555 414.3433 -60.87875 -205.5447 410.1235 -60.87875 -205.5447 415.4931 45.4564 -266.146 410.1235 32.5449 -268.0314 410.1235 58.26173 -263.6391 410.1235 -45.4564 -266.146 410.1235 -32.5449 -268.0314 410.1235 -58.26173 -263.6391 410.1235 -6.524211 -269.9212 410.1235 6.524211 -269.9212 410.1235 19.5574 -269.2908 410.1235 -70.93099 -260.5164 410.1235 -83.4346 -256.7853 410.1235 -92.694 -193.9649 410.1235 -94.74958 -252.829 410.1235 -19.5574 -269.2908 410.1235 -92.694 -193.9649 422.1527 -94.75045 -252.8405 421.125 -70 -202.2248 415.5801 -70 -202.2248 422.0085 -65 -148.1166 422.953 -119.6617 -242.0353 421.3136 -107.8284 -247.5339 421.2176 -131.2155 -235.9714 421.4194 -70 -153.116 422.8657 -65 -147.9607 417.001 -70 -152.959 416.8702 131.2155 235.9714 396.9235 142.4629 229.3563 396.9235 153.3775 222.2056 396.9235 163.9339 214.536 396.9235 174.1074 206.3652 396.9235 183.8743 197.7125 396.9235 193.2117 188.5981 396.9235 202.0979 179.0431 396.9235 210.5121 169.07 396.9235 218.4346 158.702 396.9235 225.8469 147.9634 396.9235 232.7318 136.8792 396.9235 239.0731 125.4753 396.9235 244.8561 113.7783 396.9235 250.0671 101.8156 396.9235 254.6942 89.61512 396.9235 258.7264 77.20533 396.9235 262.1543 64.61523 396.9235 264.97 51.87421 396.9235 267.1667 39.01204 396.9235 268.7395 26.05876 396.9235 269.6847 13.04461 396.9235 270 0 396.9235 269.6847 -13.04461 396.9235 268.7395 -26.05876 396.9235 267.1667 -39.01204 396.9235 264.97 -51.87421 396.9235 262.1543 -64.61523 396.9235 258.7264 -77.20533 396.9235 254.6942 -89.61512 396.9235 250.0671 -101.8156 396.9235 244.8561 -113.7783 396.9235 239.0731 -125.4753 396.9235 232.7318 -136.8792 396.9235 225.8469 -147.9634 396.9235 218.4346 -158.702 396.9235 210.5121 -169.07 396.9235 202.0979 -179.0431 396.9235 193.2117 -188.5981 396.9235 183.8743 -197.7125 396.9235 174.1074 -206.3652 396.9235 163.9339 -214.536 396.9235 153.3775 -222.2056 396.9235 142.4629 -229.3563 396.9235 119.6617 -242.0353 396.9235 131.2155 -235.9714 396.9235 107.8284 -247.5339 396.9235 95.74332 -252.4544 396.9235 70.93099 -260.5164 396.9235 83.4346 -256.7853 396.9235 58.26173 -263.6391 396.9235 45.4564 -266.146 396.9235 32.5449 -268.0314 396.9235 19.5574 -269.2908 396.9235 6.524211 -269.9212 396.9235 -6.524211 -269.9212 396.9235 -19.5574 -269.2908 396.9235 -32.5449 -268.0314 396.9235 -45.4564 -266.146 396.9235 -58.26173 -263.6391 396.9235 -70.93099 -260.5164 396.9235 -95.74332 -252.4544 396.9235 -83.4346 -256.7853 396.9235 -107.8284 -247.5339 396.9235 -119.6617 -242.0353 396.9235 -131.2155 -235.9714 396.9235 -142.4629 -229.3563 396.9235 -153.3775 -222.2056 396.9235 -163.9339 -214.536 396.9235 -174.1074 -206.3652 396.9235 -183.8743 -197.7125 396.9235 -193.2117 -188.5981 396.9235 -202.0979 -179.0431 396.9235 -221.2053 -154.892 396.9232 -210.5121 -169.07 396.9235 -221.171 -154.8656 400 -225.8469 -147.9634 400 -232.7318 -136.8792 400 -239.0731 -125.4753 400 -244.8561 -113.7783 400 -250.0671 -101.8156 400 -254.6942 -89.61512 400 -258.7264 -77.20533 400 -262.1543 -64.61523 400 -264.97 -51.87421 400 -267.1667 -39.01204 400 -268.7395 -26.05876 400 -269.6847 -13.04461 400 -269.6847 13.04461 396.9235 -270 0 400 -270 0 396.9235 -267.1667 39.01204 396.9235 -268.7395 26.05876 396.9235 -264.97 51.87421 396.9235 -262.1543 64.61523 396.9235 -258.7264 77.20533 396.9235 -254.6942 89.61512 396.9235 -250.0671 101.8156 396.9235 -239.0731 125.4753 396.9235 -244.8561 113.7783 396.9235 -232.7318 136.8792 396.9235 -225.8469 147.9634 396.9235 -218.4346 158.702 396.9235 -210.5121 169.07 396.9235 -202.0979 179.0431 396.9235 -193.2117 188.5981 396.9235 -183.8743 197.7125 396.9235 -174.1074 206.3652 396.9235 -163.9339 214.536 396.9235 -142.4629 229.3563 396.9235 -153.3775 222.2056 396.9235 -131.2155 235.9714 396.9235 -119.6617 242.0353 396.9235 -107.8284 247.5339 396.9235 -83.4346 256.7853 396.9235 -95.74332 252.4544 396.9235 -70.93099 260.5164 396.9235 -58.26173 263.6391 396.9235 -45.4564 266.146 396.9235 -32.5449 268.0314 396.9235 -19.5574 269.2908 396.9235 -6.524211 269.9212 396.9235 6.524211 269.9212 396.9235 19.5574 269.2908 396.9235 32.5449 268.0314 396.9235 45.4564 266.146 396.9235 70.93099 260.5164 396.9235 58.26173 263.6391 396.9235 83.4346 256.7853 396.9235 95.74332 252.4544 396.9235 107.8284 247.5339 396.9235 119.6617 242.0353 396.9235 -150.0614 0 396.9235 -150.0614 0 400 -150.0614 -39.64462 400 -150.0614 -39.64462 396.9235 -139.7861 -39.64462 396.9235 -139.7861 -39.64462 400 -131.9049 -61.29824 400 -119.501 -83.67549 400 -131.9049 -61.29824 396.9235 -119.501 -83.67549 396.9235 96.65456 -105.4187 506.4171 96.65456 -107.8 483.7657 96.99604 -107.8 481.3886 98.64793 -106.2125 485.0861 104.758 -100.8985 495.778 110.6252 -96.10255 505.9401 115.377 -93.30519 505.7837 123.6286 -88.84732 505.5763 132.3704 -84.64073 505.624 141.043 -80.98983 505.0627 149.3442 -77.91729 504.9375 158.1591 -75.10822 504.8005 167.3252 -72.66159 504.5719 176.3819 -70.68442 504.5147 185.576 -69.11934 504.5229 194.7915 -67.99034 504.3699 204.1874 -67.27471 504.3789 98.80941 -107.8 485.3875 139.924 -107.8 556.6871 115.3345 -93.31649 514.0966 123.5939 -88.85059 528.4024 132.6717 -84.49393 544.1257 140.7351 -107.8 558.7131 140.086 -81.36457 556.981 140.7982 -81.08151 558.9409 140.9426 -107.8 560.8858 140.9037 -81.03831 561.5568 140.5296 -107.8 563.0287 139.1552 -81.74087 565.5098 140.3983 -81.24059 563.4439 139.5295 -107.8 564.9685 138.0235 -107.8 566.548 137.5816 -82.38898 566.8966 136.1334 -107.8 567.6392 134.034 -83.90833 568.1486 135.7299 -83.1714 567.8122 134.0125 -107.8 568.1538 132.2306 -84.7079 568.1289 131.8326 -107.8 568.0499 129.6257 -85.91003 567.2913 129.7702 -107.8 567.3361 128.0096 -86.67595 566.0905 127.9924 -107.8 566.0702 126.8413 -87.22708 564.6862 126.6433 -107.8 564.3547 99.72039 -103.226 524.9028 97.95357 -104.4779 524.1965 96.65455 -105.4184 524.0036 102.1335 -101.5606 526.4701 104.3107 -100.1021 528.4145 106.8712 -98.43939 531.2601 109.8298 -96.5833 535.3461 117.6703 -92.00045 548.8131 111.3003 -107.8 537.7798 109.0859 -107.8 534.2429 106.7957 -107.8 531.1712 96.65455 -107.8 524.0036 104.2505 -107.8 528.3571 101.9492 -107.8 526.3433 99.90433 -107.8 525.0093 98.13774 -107.8 524.2612 -77.5 -77.5 409.0035 77.5 77.5 409.0035 -77.5 77.5 409.0035 77.5 -77.5 409.0035 -77.5 -77.5 447.0035 77.5 -77.5 447.0035 77.5 77.5 447.0035 -77.5 77.5 447.0035 -222.954 93.73902 396.9235 -237.2802 46.88008 396.9235 -262.7807 60.9505 396.9235 -258.7971 53.45844 396.9235 -251.9629 96.33378 396.9235 -244.4709 100.3174 396.9235 -237.2802 46.88008 384 -222.954 93.73902 384 -251.9629 96.33378 384 -244.4709 100.3174 384 -258.7971 53.45844 384 -262.7807 60.9505 384 + + + + + + + + + + 4.25207e-6 0 1 1.19823e-5 0 1 -4.63679e-5 0 1 -1.46491e-5 0 1 0 0 1 -7.57456e-6 0 1 9.48109e-5 0 1 8.50409e-6 0 1 5.99109e-6 0 1 6.8543e-5 0 1 -9.18739e-6 0 1 3.4289e-6 0 1 -1.50622e-5 0 1 0.03274595 -0.9994454 0.006069302 0.239715 -0.9708199 0.006752312 0.4362456 -0.8997961 0.007550418 0.6138699 -0.7893615 0.008495986 0.7647644 -0.6442394 0.009545862 0.8822802 -0.4706043 0.01064831 0.9594193 -0.2817594 0.01123952 0.9944688 -0.1045066 0.010508 0.9902867 -0.1390416 0 0.9983685 0.05681127 -0.005742132 0.9944721 0.1045238 0.01001065 0.9510419 0.3090301 -0.004426777 0.9610496 0.2761318 0.01161724 0.86602 0.4999918 -0.004210293 0.8822774 0.4706097 0.01064759 0.743142 0.6691225 -0.003875017 0.7647593 0.6442456 0.009545266 0.587789 0.8090068 -0.003488063 0.6138539 0.7893741 0.008494138 0.4067355 0.9135408 -0.003109872 0.4362467 0.8997955 0.007551968 0.2079101 0.9781441 -0.002766966 0.2397258 0.9708172 0.006752073 0 0.999997 -0.002472996 0.03274244 0.9994454 0.006067931 -0.2079149 0.9781447 -0.00208795 -0.1456162 0.9892591 0.01274657 -0.406724 0.9135212 -0.007402837 -0.3635568 0.93156 0.004764497 -0.5877907 0.8090114 -0.001619219 -0.5618812 0.8272093 0.003798723 -0.7431411 0.6691334 -0.001400291 -0.7209273 0.6930022 0.00342983 -0.8660271 0.4999957 -0.001258015 -0.8487765 0.5287421 0.003202378 -0.951048 0.3090415 -0.001168549 -0.9398823 0.3414849 0.003068566 -0.9945229 0.1045135 -0.001115381 -0.9917555 0.1281335 0.001691162 -0.9917564 -0.1281273 0.001690864 -0.9398895 -0.3414651 0.003068983 -0.8487826 -0.5287323 0.00320208 -0.720918 -0.693012 0.003429949 -0.5618801 -0.8272101 0.0037992 -0.363848 -0.9314462 0.004755973 -0.1465704 -0.989121 0.0125221 -0.20791 -0.9781457 -0.002088189 -0.4067276 -0.9135206 -0.007277727 -0.5877922 -0.8090104 -0.001618623 -0.743147 -0.6691268 -0.001400589 -0.866026 -0.4999974 -0.001258194 -0.9510423 -0.3090585 -0.001168429 -0.9945218 -0.1045237 -0.001114904 0.9510478 -0.3090439 0 0.8660173 -0.4999963 -0.004211246 0.743136 -0.6691292 -0.003875017 0.5877833 -0.809011 -0.0034886 0.4067258 -0.9135451 -0.003109216 0.2079113 -0.9781439 -0.002765893 0 -0.999997 -0.002473056 -0.7880311 8.59206e-5 0.6156356 -0.7887367 -1.04061e-4 0.6147313 -0.7880102 0 0.6156622 -0.7880154 -2.41355e-6 0.6156556 -0.7880089 0 0.6156638 -0.7880084 0 0.6156645 -0.7880694 3.90957e-5 0.6155865 -0.7880116 2.42256e-6 0.6156605 -0.7880041 1.47086e-6 0.6156701 -0.7880213 1.92653e-6 0.615648 -0.789787 -0.00105983 0.6133804 -0.7880176 1.26214e-6 0.6156527 -0.7880067 4.50351e-6 0.6156668 -0.7879977 -2.86017e-5 0.6156783 -0.7880167 1.24584e-6 0.6156538 -0.7880055 3.25784e-6 0.6156684 -0.7880181 -8.45023e-6 0.6156522 -0.7880157 6.16637e-6 0.6156552 -0.7880128 -1.10411e-5 0.6156589 -0.7880156 -7.02066e-6 0.6156554 -0.7885838 0.001559138 0.6149254 -0.7880122 0 0.6156598 -0.788009 -7.19646e-7 0.6156638 -0.7880041 2.13084e-5 0.6156701 -0.7880047 4.24137e-6 0.6156692 -0.7879877 1.80069e-5 0.6156911 -0.7880326 -2.13061e-5 0.6156336 -0.7879951 -2.50309e-5 0.6156817 -0.7880067 1.13005e-5 0.6156666 -0.7880132 -3.31432e-5 0.6156585 0.001346468 0.9999986 -0.001053273 0 1.17069e-4 1 0.6706293 0.7417927 0 0.6683436 0.7438527 -3.58435e-4 0.7147894 0.6993397 3.0291e-4 0.7105675 0.703629 -3.37628e-4 0.7481076 0.6635774 -2.68187e-4 0.7829467 0.6220886 -5.76284e-4 0.7925125 0.6098554 5.37107e-4 0.8165275 0.5773065 -4.50622e-4 0.8419575 0.5395439 -1.1952e-4 0.8393663 0.5435663 9.46929e-5 0.8218197 0.5697478 3.65687e-5 0.7511919 0.660084 9.28972e-5 -0.194911 -0.980821 -1.10828e-5 -0.194765 -0.9808499 0 -0.1949242 -0.9593968 -0.2038689 0.8424701 0.5269468 0.1121218 0.823206 0.5554006 0.1177381 0.7999067 0.5870578 0.1245493 0.776836 0.6150054 0.1352564 0.7473869 0.6494231 0.140223 0.7487702 0.6480818 0.1390442 0.7100683 0.6885835 0.1471594 0.6691417 0.7264984 0.1563633 0.6715707 0.7246793 0.1543788 0.7102518 0.6883757 0.147246 0.7832986 0.6081278 0.128934 0.8153927 0.5655868 0.123477 0.8413593 0.5285568 0.1128821 0.6732141 0.7394477 4.54417e-5 0.6669995 0.745058 5.09288e-4 0.6330686 0.7740955 -5.51941e-4 0.5963624 0.8027153 -3.36911e-4 0.5567884 0.8306544 -2.24713e-4 0.00509262 0.9999871 0 0.002291679 0.9999971 -8.88928e-4 0.03089797 0.9995221 0.001021087 0.04438394 0.9990115 -0.002460062 0.06758087 0.9977123 0.001736819 0.09343695 0.9956226 -0.002263307 0.1423978 0.9898095 -2.44773e-4 0.1413763 0.9899558 -6.11064e-4 0.1841144 0.9829028 -0.001994967 0.1868394 0.9823902 -6.85317e-4 0.236757 0.9715669 -0.002001166 0.2548522 0.9669795 0.001045703 0.275476 0.961307 -0.001371145 0.3054403 0.9522097 -0.001767396 0.3212473 0.9469948 0.001113712 0.3471446 0.9378103 -0.001554012 0.3487072 0.9372312 -0.001077294 0.3685926 0.9295909 6.3882e-4 0.3887913 0.9213255 -8.71994e-4 0.3925478 0.9197316 -8.43436e-5 0.4231595 0.9060552 1.8137e-4 0.4190467 0.9079636 -0.001431882 0.4413095 0.8973547 5.99682e-4 0.464576 0.8855329 -9.88022e-4 0.4623336 0.8867044 -0.001757681 0.4820451 0.8761462 6.48413e-4 0.5049066 0.8631737 -6.70049e-4 0.5026093 0.864513 -0.001220345 0.5244619 0.851434 -7.34726e-5 0.5161257 0.8565129 -1.03247e-4 0.5418128 0.8404992 2.76042e-4 0.5521485 0.8337454 7.98056e-4 0.5591063 0.8290959 6.77464e-4 0.5525028 0.8335108 8.21598e-4 0.6070771 0.7946429 2.17676e-4 0.5504024 0.8348996 -2.03464e-4 0.5389735 0.8423224 -8.87791e-4 0.5389514 0.8423365 -8.89965e-4 0.5442155 0.8389455 -4.20325e-4 0.5586948 0.8293734 -1.06896e-4 0.5194209 0.8545179 0.001019358 0.5308201 0.8474846 2.04518e-4 0.5020734 0.8648251 2.84913e-5 0.4831483 0.8755381 0.001018464 0.465293 0.8851563 9.58844e-4 0.4418678 0.8970787 0.001664817 0.4088932 0.9125531 -0.00731343 0.4358818 0.8999611 0.008790671 0.475138 0.8799042 0.003538191 0.5157429 0.8567417 0.001732468 0.285003 0.9585265 4.54658e-4 0.2177135 0.9760113 0.001625537 0.1025578 0.9947269 4.7565e-4 0.5652452 0.8249229 2.75004e-4 0.6016575 0.7987543 2.28506e-4 0.6400894 0.7683005 3.30957e-4 0.6719395 0.7406051 0.001259744 -7.4349e-6 0 1 1.8475e-5 0 1 5.45699e-6 0 1 -3.98911e-4 5.40538e-5 1 -0.661785 0 0.7496938 -0.6522434 0.009028077 0.7579559 -0.6093026 -0.004319489 0.792926 -0.593793 0.008032798 0.8045778 -0.5532503 -0.002591907 0.8330111 -0.5320214 0.007410228 0.8466985 -0.4672573 0.006912946 0.8840944 -0.4113495 0 0.9114778 -0.399897 0.006335079 0.9165383 -0.3538249 -0.002073705 0.9353095 -0.3302704 0.00608021 0.9438668 -0.2588132 0.00587666 0.9659096 -0.1859219 0.005688965 0.9825481 -0.1243351 0 0.9922403 -0.1119499 0.005545377 0.9936985 -0.04754674 -0.004039585 0.9988608 -0.0373761 0.001940786 0.9992994 0.0293067 0.001929163 0.9995687 0.03738903 0.004994332 0.9992883 0.1273028 -3.69504e-4 0.9918639 0.1119537 0.00600773 0.9936953 0.1788249 9.83584e-4 0.9838805 0.1859164 0.004264593 0.9825564 0.2758659 -9.81708e-4 0.9611957 0.2330419 -0.001020193 0.9724662 0.2588211 0.004861295 0.9659131 0.3302783 0.002064943 0.9438813 0.3247933 0.004839181 0.9457727 0.3998935 0.005894064 0.9165427 0.365444 -0.001623392 0.9308319 0.4832285 -0.003513753 0.8754872 0.4672743 0.003296375 0.8841063 0.5435494 -0.001118183 0.8393766 0.5320361 0.003284215 0.8467154 0.597118 4.81382e-4 0.8021533 0.5938218 0.001994371 0.8045942 0.6420783 0.004911482 0.7666233 0.6522899 -6.05114e-4 0.7579694 0.7071003 0.002963781 0.7071071 0.7581887 3.98774e-4 0.6520352 0.7579801 5.11722e-4 0.6522777 0.8045901 -4.64032e-4 0.5938304 0.8019847 9.94464e-4 0.5973438 0.8467188 9.34367e-5 0.5320408 0.844344 0.001452863 0.5357998 0.8841175 -0.001236736 0.4672629 0.8758362 0.004099667 0.4825911 0.9116024 0.001520991 0.4110701 0.9165593 -0.002492189 0.399891 0.9397681 0.002628564 0.3418027 0.9438852 -6.02814e-4 0.3302733 0.9659223 -0.00134474 0.258829 0.962065 0.002642095 0.2728078 0.9808707 0.001087129 0.1946581 0.982565 -0.001270115 0.1859153 0.9937129 -4.35856e-4 0.1119577 0.9919577 0.002973794 0.1265353 0.9992982 0.002207696 0.03739464 0.9982653 -0.001052141 0.05886739 0.9992991 0.001741707 -0.03739464 0.9997896 -0.001130104 -0.02048468 0.9950807 -7.44315e-4 -0.09906595 0.984076 -8.5247e-4 -0.1777469 0.9703966 -5.57155e-4 -0.2415168 0.953106 -9.48582e-4 -0.3026353 0.9351526 0.005639791 -0.3542003 0.9109408 0.003039181 -0.4125261 0.8780788 0.00189346 -0.4785126 0.8377847 0.00416857 -0.5459849 0.8049663 7.85687e-4 -0.5933201 0.7609222 -6.68082e-4 -0.6488429 0.7071015 0.002852141 -0.7071064 0.7163482 -8.82645e-4 -0.6977424 0.6749776 -0.00155574 -0.7378367 0.6402004 0.006269752 -0.7681823 0.5914356 0.001738965 -0.8063504 0.5320185 -3.16754e-4 -0.8467327 0.5276603 0.002731144 -0.8494513 0.4725506 1.5431e-4 -0.8813036 0.3998781 0.004471659 -0.9165575 0.4078608 -0.001140058 -0.9130434 0.3302791 0.007107138 -0.9438566 0.3436886 -0.002510786 -0.9390804 0.2587899 0.006191611 -0.9659139 0.271547 -0.00475955 -0.9624135 0.1859271 0.009800136 -0.9825147 0.2025443 -0.003356635 -0.9792674 0.1379972 -0.005466282 -0.9904175 0.1119505 0.01217806 -0.9936392 0.075369 -0.005911707 -0.9971383 0.03739959 0.01190298 -0.9992295 -0.03739941 0 -0.9993004 -0.111964 0 -0.9937123 -0.1859078 0 -0.9825673 -0.2588182 0 -0.9659261 -0.3302751 0 -0.9438847 -0.3999043 0 -0.916557 -0.4672748 0 -0.8841122 -0.532033 0 -0.8467237 -0.5938086 0 -0.8046064 -0.6522945 0 -0.7579658 -0.7071156 0 -0.707098 -0.7579659 0 -0.6522943 -0.8046044 0 -0.5938113 -0.8467189 0 -0.5320407 -0.8841121 0 -0.4672749 -0.9165658 0 -0.399884 -0.9438799 0 -0.330289 -0.9659278 0 -0.2588121 -0.9825662 0 -0.1859132 -0.9937131 0 -0.1119575 -0.9993006 0 -0.03739464 -0.9993006 0 0.03739464 -0.9937131 0 0.1119575 -0.9825662 0 0.1859132 -0.9659278 0 0.2588121 -0.9438818 0 0.3302839 -0.9165632 0 0.39989 -0.8841158 0 0.4672681 -0.8467282 0 0.5320257 -0.8046044 0 0.5938113 -0.7544405 0 0.6563686 -0.7070559 0.01261454 0.7070452 -0.6974499 0 0.7166336 -0.7579415 -0.007975876 0.652274 -0.8045927 0 0.5938271 -0.8467189 0 0.5320407 -0.8841194 0 0.4672612 -0.9165605 0 0.3998961 -0.9438799 0 0.330289 -0.9659266 0 0.2588163 -0.9659266 0 -0.2588163 -0.9438818 0 -0.3302839 -0.9165632 0 -0.39989 -0.8841158 0 -0.4672681 -0.8467282 0 -0.5320257 -0.8045927 0 -0.5938271 -0.6522849 0 -0.7579739 -0.5938193 0 -0.8045985 -0.5320448 0 -0.8467163 -0.4672489 0 -0.8841259 -0.3998904 0 -0.916563 -0.3302899 0 -0.9438796 -0.2588027 0 -0.9659302 -0.1859238 0 -0.9825642 -0.1119476 0 -0.9937142 -0.03739368 0 -0.9993007 0.02111935 0 -0.999777 0.4672557 0.003674924 -0.8841147 0.5938277 1.30563e-4 -0.8045924 0.6522969 -0.001515567 -0.7579621 0.7579749 7.93503e-4 -0.6522833 0.8045902 9.71474e-4 -0.5938299 0.8467227 -0.001131772 -0.5320333 0.8841153 -0.002559304 -0.4672617 0.9165629 -9.2104e-4 -0.3998896 0.9438829 -0.001931011 -0.3302747 0.9659215 0.002218544 -0.258826 0.9825655 7.68232e-4 -0.1859151 0.9937118 0.001546502 -0.1119577 0.7143711 1.37477e-4 0.6997672 0.6763943 -0.001033425 0.736539 0.4228612 -0.001557588 0.9061932 0.06863367 -0.001563787 0.9976408 -0.1737037 0 0.984798 -0.2408786 -0.00288093 0.9705511 -0.3067567 -0.001986145 0.9517859 -0.456302 0 0.8898251 -0.510961 -0.00236988 0.8596007 0.004593729 0.9782935 0.2071729 0.02026474 0.9772897 0.2109364 0.02857053 0.9776396 0.2083379 0.06087219 0.9756206 0.2108528 0.06964522 0.9759792 0.2064323 0.09025985 0.9744302 0.2057645 0.1198862 0.9708813 0.207405 0.1447474 0.9681225 0.2044192 0.1715785 0.9636105 0.204977 0.1936655 0.959783 0.2032496 0.2287449 0.9514572 0.2059249 0.2600101 0.9448571 0.1990973 0.2951817 0.9345483 0.1987141 0.3278468 0.9234829 0.1992384 0.3495814 0.9165096 0.1944302 0.3687797 0.9092775 0.1929144 0.3880937 0.9011188 0.1933086 0.3931016 0.8992567 0.1918552 0.4303169 0.8830241 0.1873391 0.4361451 0.8804978 0.1857445 0.4752905 0.8609134 0.1814581 0.514336 0.8390269 0.1774612 0.5533273 0.8146704 0.1736122 0.5591835 0.8110953 0.1715759 0.5914649 0.7887533 0.1674441 0.6250362 0.7633196 0.1633189 0.6570814 0.7372296 0.1572787 0.6651463 0.7311472 0.1516717 0.6755943 0.7210037 0.1540328 0.632125 0.7581054 0.1602945 0.5960781 0.7855357 0.1662069 0.5502237 0.8167668 0.1736261 0.507119 0.8429821 0.1794763 0.4643324 0.8662511 0.1844036 0.4077228 0.8932074 0.1895854 0.3352661 0.9215249 0.1959298 0.2862406 0.9367547 0.2013876 0.2418798 0.9496738 0.1990323 0.2091689 0.9560135 0.205637 0.1644884 0.9643612 0.2072464 0.1154488 0.971061 0.2090747 0 1 0 0 1 -3.38533e-7 0 1 -1.83979e-7 0 1 -1.89093e-7 0 1 1.80627e-7 -3.0915e-4 0.9999987 -0.001595437 0 1 1.86043e-7 0 1 3.83313e-7 2.66703e-4 1 -8.66401e-6 2.47346e-4 1 0 1 0 0 -0.1706774 -4.12028e-6 -0.985327 -0.1706892 1.18547e-5 -0.9853249 -0.1706693 -5.69688e-7 -0.9853284 -0.1706869 2.11015e-6 -0.9853254 -0.1706716 2.91853e-7 -0.985328 -0.1706835 -2.29327e-6 -0.9853259 -0.1702256 -2.98102e-5 -0.9854052 -0.1706812 -3.99111e-6 -0.9853264 -0.1706851 4.32405e-6 -0.9853256 -0.1706814 1.7952e-6 -0.9853263 -0.1706814 7.06806e-7 -0.9853263 -0.1706932 0 -0.9853242 0.5363983 4.61537e-6 -0.8439649 0.5364336 -1.16385e-5 -0.8439425 0.5363992 -1.17552e-6 -0.8439645 0.5363997 9.11054e-7 -0.843964 0.5365324 0 -0.8438798 0.5363205 8.69281e-6 -0.8440145 -0.898795 0 -0.4383694 -0.8987958 0 -0.4383677 -0.7012861 0 0.7128799 -0.7012866 0 0.7128794 9.93553e-7 0.9781476 0.2079117 4.86251e-7 0.9781477 0.2079113 -5.88388e-6 0.9781471 0.2079144 6.14408e-6 0.9781491 0.2079049 1.91416e-6 0.9781484 0.2079082 -7.63692e-6 0.978147 0.2079151 -5.66939e-6 0.978147 0.2079148 -1.06491e-6 0.9781475 0.2079125 5.57277e-6 0.9781479 0.2079102 -0.001913368 0.9783021 0.2071753 1.20903e-6 0.9781482 0.2079091 -5.76114e-7 0.9781477 0.2079115 -4.82685e-4 0.9781535 0.2078837 6.2555e-6 0.9781474 0.2079126 5.92621e-7 0.9781477 0.2079114 -9.65565e-5 0.9781277 0.2080054 8.62662e-4 0.9802911 0.1975569 3.26014e-4 0.9781476 0.2079116 -6.45342e-5 0.9781309 0.2079902 0 1 -2.5536e-7 0 1 1.85876e-7 -0.6081956 -5.04301e-7 0.7937873 -0.6081922 -4.06567e-6 0.7937899 -0.6081958 -3.9592e-6 0.7937871 -0.6082047 7.92197e-7 0.7937802 -0.6082153 2.03807e-6 0.7937722 -0.6081999 7.94078e-7 0.7937839 -0.6081956 0 0.7937872 -0.6082109 5.41913e-6 0.7937754 -0.608192 -5.33545e-6 0.7937901 -0.6081919 -5.67555e-6 0.7937901 -0.6081977 0 0.7937856 -0.6082006 0 0.7937835 -0.608199 0 0.7937846 0.6174229 0 0.7866314 0.6174264 0 0.7866288 -0.3452278 0 0.938519 -0.3452278 0 0.938519 0.009427666 0.9777677 0.2094791 0.003018856 0.9781426 0.2079135 0.03520226 0.9778625 0.2062665 0.05678039 0.9760337 0.2100819 0.08352428 0.975162 0.205141 0.1087477 0.9718832 0.2088472 0.1348054 0.9696454 0.2039986 0.1554636 0.966017 0.2065006 0.185975 0.9610807 0.2042966 0.1805915 0.9622734 0.2035109 0.2137435 0.9558787 0.2015184 0.2194653 0.9542673 0.2030001 0.2372778 0.9500724 0.2026369 0.2621405 0.9441817 0.1995074 0.2923221 0.9355223 0.1983583 0.2946627 0.9346928 0.1988047 0.3290724 0.9235396 0.1969413 0.3531144 0.9148248 0.1959745 0.3828695 0.904136 0.1896026 0.3264904 0.9246274 0.1961332 0.2638265 0.943663 0.1997398 5.55437e-5 1 1.88533e-4 -2.98988e-5 1 1.04225e-4 -3.16798e-5 1 8.58271e-5 0 1 9.23535e-7 0.9993917 0.03487378 3.69123e-4 0.9993909 0.03490012 0 0.9990195 0 0.04427522 0.9990274 9.80603e-6 0.04409408 0.9989848 -2.83756e-5 0.04504811 0.9990278 0 0.04408448 0.9990273 -4.09942e-5 0.04409778 0.9990274 -5.84113e-5 0.0440942 1.53863e-4 1 1.78151e-5 2.32197e-5 1 -2.50088e-6 -7.05086e-5 1 -3.18926e-6 1.08301e-4 1 -9.37071e-6 -2.31065e-4 1 -2.58711e-5 -2.99856e-7 3.97206e-4 -1 0.2901055 0.1453915 0.9458859 0.280615 0.1418855 0.9492754 0.2896372 0.1755725 0.9408957 0.3110204 0.1996101 0.9292051 0.2832604 0.1901779 0.9399979 0.2634891 0.1992009 0.943871 0.2590255 0.2211052 0.9402225 0.2819662 0.2300945 0.9314246 0.2391278 0.231187 0.9430645 0.2535058 0.2616797 0.9312672 0.2170716 0.2490683 0.9438459 0.2185627 0.2793592 0.9349807 0.2035148 0.271578 0.9406526 0.1843036 0.2816149 0.941661 0.1864736 0.2949958 0.937126 0.1632186 0.3010416 0.9395391 0.1608829 0.2993048 0.9404964 0.1437325 0.3112973 0.9393801 0.1437408 0.3111913 0.939414 5.57788e-6 0.01745194 0.9998478 1.61418e-6 0.01745152 0.9998477 0 0.01745212 0.9998478 1.11145e-5 0.01744931 0.9998478 0 0.0174511 0.9998478 -6.29526e-5 0.01745319 0.9998477 -3.37113e-5 0.01747059 0.9998474 -5.17455e-6 0.01745241 0.9998477 5.98801e-6 0.01745074 0.9998478 3.09597e-5 0.01745003 0.9998478 1.29881e-6 0.01745021 0.9998478 1.05904e-4 0.01745623 0.9998477 0 0.01745057 0.9998478 0 0.02161973 0.9997664 4.84736e-5 0.0173698 0.9998492 0 0.01745271 0.9998477 -1 -4.04656e-5 2.94586e-4 -1 3.42172e-7 -9.92357e-6 -0.01296985 0.3420918 0.9395771 -0.01063919 0.342764 0.9393613 0.007179379 0.341776 0.9397541 0.01205062 0.3425098 0.939437 0.02746641 0.3400381 0.9400106 0.04712623 0.339904 0.9392787 0.08137524 0.3328292 0.9394695 0.2916339 0.1767939 0.9400498 0.2879327 0.178925 0.9407873 0.2852874 0.1915362 0.9391086 0.2789005 0.1918164 0.9409682 0.2683513 0.2064055 0.9409486 0.2733473 0.2066473 0.9394563 0.2602638 0.2221784 0.9396273 0.2569122 0.2217221 0.9406569 0.245083 0.2376039 0.9399355 0.2461133 0.2379338 0.9395828 0.2280544 0.2463433 0.9419693 0.2294215 0.2632268 0.9370579 0.2152183 0.2600297 0.9413107 0.2046077 0.2763523 0.9390235 0.1869053 0.2855821 0.9399518 0.188929 0.2868708 0.9391545 0.1681852 0.2898513 0.9421784 0.1654968 0.3052392 0.9377846 0.1523904 0.3004521 0.9415443 0.1354621 0.3116645 0.9404867 0.1442649 0.3122707 0.9389754 0.1361824 0.3101547 0.9408817 0.1200326 0.3208957 0.9394776 0.1029474 0.3260937 0.9397153 0.1011128 0.3269633 0.9396123 -0.04284662 0.3398308 0.9395102 -0.04374217 0.3399133 0.939439 0.1227726 0.3204836 0.9392642 0.2039657 0.272198 0.9403757 0.0834279 0.3319021 0.9396173 0.06539767 0.3350473 0.9399291 0.04819542 0.3400574 0.9391689 -0.0285865 0.3400574 0.9399701 0.9809229 0.1594762 -0.1111651 2.81509e-6 0 1 3.31944e-6 -2.15918e-7 1 -3.83859e-6 2.27901e-6 1 1.17729e-6 0 1 -8.70831e-7 0 1 8.40064e-7 0 1 4.24208e-6 0 1 -2.76475e-7 2.41411e-7 1 -3.69301e-6 2.28579e-6 1 -3.77092e-6 0 1 1.43798e-6 3.77443e-7 1 3.4499e-6 -1.23448e-6 1 -3.41324e-5 4.07037e-6 1 0.9993907 0.03490501 1.38302e-5 0.9993909 0.03489905 4.2486e-5 -9.5066e-6 0.01745182 0.9998477 7.23252e-6 0.01745283 0.9998477 -7.27314e-6 0.01745098 0.9998478 2.73072e-6 0.01745373 0.9998478 -1.40034e-6 0.0174514 0.9998477 -1.79481e-6 0 1 -8.71632e-7 0 1 -1.4388e-5 -8.67866e-7 1 -4.54267e-6 0 1 -3.667e-7 0 1 -4.02072e-7 6.28187e-7 1 1.41308e-6 -1.78057e-7 1 -1.29999e-6 -4.69865e-7 1 3.68551e-6 1.40515e-7 1 5.37249e-6 1.96958e-7 1 2.16222e-6 0 1 0 -2.31468e-7 1 -2.48963e-6 -1.22366e-7 1 -8.72626e-6 0 1 2.78557e-6 -1.49197e-7 1 -2.65219e-6 -4.31892e-7 1 7.98996e-6 0 1 4.24994e-5 -2.16591e-5 1 -5.59518e-7 0 1 -3.05074e-7 0 1 -5.97487e-6 4.37175e-6 1 5.07221e-6 0 1 2.78791e-6 -2.51912e-7 1 3.52856e-6 0 1 -2.569e-6 -1.7635e-7 1 -4.58429e-6 0 1 0 -1.19708e-7 1 0 -2.30211e-7 1 0 -5.01055e-7 1 7.6782e-6 2.61381e-6 1 5.73538e-7 0 1 7.87231e-6 0 1 -7.85464e-6 0 1 -1.24816e-6 0 1 -2.26139e-6 0 1 -1.34439e-6 -3.38805e-7 1 4.79214e-6 0 1 -2.53414e-6 0 1 0 -2.05356e-7 1 6.70424e-6 -3.09568e-6 1 0 2.68147e-6 1 5.39078e-6 0 1 -6.678e-7 -2.8614e-7 1 0 0 1 0 0 1 0 -4.21394e-6 1 9.68267e-6 0 1 2.79128e-6 0 1 0 -5.25189e-7 1 0 -3.87855e-7 1 -3.49139e-6 0 1 0.9993924 -0.03484934 6.49098e-4 0.999375 -0.03517597 -0.003515183 0.7071081 2.30199e-7 -0.7071055 0.7071032 -2.28562e-7 -0.7071104 0.7071108 4.5844e-7 -0.7071028 0.7071083 -6.56433e-7 -0.7071053 0.7070652 2.69152e-6 -0.7071484 0.7071127 -2.57792e-6 -0.7071009 0.7071079 1.60234e-6 -0.7071057 0.7070879 1.76724e-5 -0.7071258 0.7071152 -2.60314e-6 -0.7070983 0.707107 0 -0.7071067 0.7071073 7.91607e-7 -0.7071064 0.7070885 1.57384e-5 -0.7071251 0.7070977 0 -0.707116 -0.9993909 0.03489828 -5.0849e-6 -0.9993895 0.03493678 1.76429e-4 -0.9993895 0.03493899 1.1852e-4 3.36015e-6 0 1 1.71225e-6 7.88104e-6 1 -3.40836e-6 0 1 1.0333e-6 0 1 -1.70289e-6 0 1 -3.09311e-6 0 1 -3.45669e-6 0 1 -2.74577e-6 0 1 3.13418e-6 0 1 8.51307e-7 0 1 3.1798e-6 0 1 0.04843384 0.3595751 0.9318583 0.04843026 0.3595681 0.9318612 0.04843008 0.3595641 0.9318628 0.04843401 0.3595737 0.9318589 0.04843419 0.3595783 0.9318571 0.04842936 0.359566 0.9318621 0.04843455 0.3595727 0.9318593 0.04843801 0.359575 0.9318581 0.04843139 0.3595685 0.9318609 0.04843729 0.3595693 0.9318605 0.04842585 0.3595688 0.9318612 0.04843288 0.3595756 0.9318582 0.04843109 0.359571 0.93186 0.04843425 0.3595755 0.9318582 0.04842644 0.3595662 0.9318622 0.04843163 0.3595688 0.9318609 0.04843354 0.3595736 0.9318589 0.04843342 0.3595696 0.9318605 0.04843401 0.359574 0.9318588 0.04843682 0.3595765 0.9318577 0.04842418 0.3595665 0.9318622 0.04844254 0.3595772 0.9318571 0.04843282 0.3595711 0.93186 0.04842287 0.3595662 0.9318624 0.04843294 0.3595718 0.9318597 0.04842936 0.3595699 0.9318606 0.04843235 0.359575 0.9318585 0.04843318 0.3595709 0.93186 0.04843622 0.3595758 0.931858 0.04843175 0.3595708 0.9318602 0.04843366 0.3595727 0.9318593 0.04843223 0.3595707 0.9318602 0.04842948 0.3595708 0.9318602 0.04843252 0.3595727 0.9318593 0.04843318 0.3595699 0.9318604 0.04842668 0.3595687 0.9318612 0.04843318 0.3595688 0.9318608 0.04844176 0.3595798 0.9318562 0.04843324 0.35957 0.9318604 0.04846018 0.3595795 0.9318554 0.04843538 0.3595803 0.9318563 0.0484488 0.3595561 0.9318649 -0.9987322 0.003220021 0.05023854 -0.704839 0.6729617 -0.2243314 -0.7380743 0.6414809 -0.2091619 -0.772089 0.6053541 -0.1934559 -0.8040021 0.5676008 -0.1772292 -0.833748 0.5282971 -0.1605197 -0.8612366 0.4875613 -0.1433727 -0.886385 0.4455179 -0.1258394 -0.9091364 0.4022616 -0.1079668 -0.9293717 0.3583225 -0.0887323 -0.9204164 0.3783802 -0.0982961 -0.9472018 0.3125902 -0.07138812 -0.9624065 0.2664347 -0.05278688 -0.975008 0.2195466 -0.03404003 -0.9849666 0.1720748 -0.01520329 -0.9922598 0.1241255 0.003676295 -0.9968649 0.07584303 0.02254599 -0.9988009 0.02410501 0.04261088 -0.9987001 0.02912551 0.04183214 -0.9968651 0.07584023 0.02254587 -0.99226 0.124123 0.003676533 -0.9849675 0.1720692 -0.01520293 -0.9750078 0.2195477 -0.03404057 -0.9624071 0.2664324 -0.05278652 -0.9472 0.3125954 -0.0713889 -0.9310001 0.3541832 -0.08827996 -0.9088411 0.4029154 -0.1080141 -0.8863877 0.4455126 -0.1258392 -0.861232 0.4875692 -0.1433728 -0.8337464 0.5282993 -0.1605203 -0.8040041 0.5675978 -0.1772298 -0.7720878 0.6053559 -0.1934553 -0.7380732 0.6414818 -0.2091631 -0.7038188 0.6742736 -0.223594 -0.04843384 -0.359588 -0.9318534 0.01535946 -0.9331259 0.3592218 0.01549875 -0.9329842 0.3595834 0.01537019 -0.9331128 0.3592553 0.01537144 -0.9331099 0.3592629 0.01536291 -0.9331107 0.359261 -4.14291e-6 0.3583667 0.9335809 -9.57308e-5 0.3583003 0.9336064 -2.24657e-5 0.3583757 0.9335775 0 0.3583676 0.9335806 -7.94534e-6 -0.4067367 0.9135454 -1.29285e-4 -0.4066886 0.913567 2.89639e-5 -0.4067149 0.9135553 0.4226157 0.906309 0 0.422614 0.9063098 -6.95745e-6 0.4226051 0.906314 9.20352e-5 0.4226223 0.906306 0 -0.9563046 0.2923727 0 -0.9563047 0.2923722 0 9.70835e-6 0 1 -5.76675e-6 0 1 -6.22313e-6 0 1 5.18215e-6 0 1 3.82283e-6 0 1 2.65022e-6 0 1 0.2923678 0.956306 0 0.2920988 0.9563881 3.91489e-4 0.2164387 0.9762962 0 0.06104606 0.998135 0 -0.09584343 0.9953964 0 -0.2503746 0.9681491 0 -0.3987438 0.9170624 0 -0.5372942 0.8433949 0 -0.6626244 0.7489519 0 -0.771622 0.6360813 0 -0.8616322 0.5075334 0 -0.9304155 0.3665066 0 -0.9304149 0.3665081 0 -0.8616403 0.5075195 0 -0.7716285 0.6360736 0 -0.6626194 0.7489563 0 -0.5373035 0.843389 0 -0.3987505 0.9170595 0 -0.2503783 0.9681481 0 -0.09584659 0.9953961 0 0.06104904 0.9981349 0 0.2164455 0.9762947 0 -4.98212e-6 0 1 -3.86286e-6 0 1 1.13272e-5 9.3523e-7 1 3.80141e-6 2.63029e-6 1 0 -2.45617e-6 1 -1.26578e-5 1.12335e-6 1 -9.90276e-6 8.09684e-7 1 -3.02312e-6 0 1 0 9.80709e-7 1 -1.76393e-7 1.12059e-6 1 4.47647e-6 0 1 0 7.13507e-7 1 0 1.03682e-6 1 8.08265e-7 1.00661e-5 1 -7.81063e-7 -4.96192e-6 1 0 1.92581e-6 1 -0.9999991 0 -0.001409888 0 -1 5.10921e-5 -6.38779e-6 -1 0 0 0 -1 0 -1 0 -1 -3.77377e-5 -1.64689e-4 -0.9999997 -9.85761e-5 -8.10868e-4 -1 -1.07367e-4 0 -1 0 0 -1 2.41553e-7 0 0 -0.9335817 0.3583645 0 -0.933583 0.3583614 -2.96958e-6 -0.9335805 0.3583678 0.001620829 -0.9333251 0.3590289 0.009856104 -0.9999514 2.37307e-4 -0.8746186 -0.4848119 0 -0.9396936 -0.3420175 -1.09892e-4 -0.9396961 -0.3420106 0 -0.9396935 -0.3420178 2.0182e-6 -0.9396939 -0.3420167 3.12666e-6 -0.9397987 -0.3417288 -4.43214e-7 -0.9396919 -0.3420221 0 1.33057e-4 0 1 2.84588e-5 0 1 -0.5735473 0.8191725 7.4269e-6 -0.5736622 0.819092 0 0 1.56696e-5 1 -5.76577e-6 0 1 0.5735661 -0.8191592 0 0.5786285 -0.8155789 0.004488825 0.01059246 -0.01515656 0.9998291 0.01061373 -0.01515942 0.9998288 0.01060622 -0.01515322 0.999829 0.01062458 -0.01515167 0.9998289 -0.496732 0.7094063 0.5 -0.4967321 0.7094063 0.5000001 -0.4850218 0.6919673 0.5347291 0.8191522 0.5735763 0 0.8191631 0.5735607 0 0.8191479 0.5735825 1.26366e-6 0.8191505 0.5735787 0 0.8191725 0.5735473 0 0.8193299 0.5733225 -2.18113e-4 0.8191525 0.5735759 2.26628e-7 0.8191526 0.5735756 5.50259e-7 0.8191611 0.5735635 0 0.8191417 0.5735912 0 0.8191518 0.5735768 0 0.5735769 -0.8191519 0 0.5735763 -0.8191522 0 -1.24695e-6 0 1 1.05007e-6 0 1 0.573584 -0.8191468 0 0.5735841 -0.8191467 0 -0.8191775 -0.5735403 0 -0.819155 -0.5735722 0 -0.8191517 -0.5735771 -1.13314e-6 -0.8191515 -0.5735774 0 -0.8203372 -0.5718801 0 -0.8191515 -0.5735772 -2.68033e-7 -0.8191531 -0.573575 -2.436e-7 -0.8191441 -0.573588 0 -0.5735008 0.8192051 2.45698e-4 -0.5735754 0.8191528 0 5.84575e-7 0 1 1.17999e-6 0 1 -1.18933e-6 0 1 8.87874e-6 3.32187e-5 1 1.23297e-5 2.13826e-6 1 2.40622e-6 0 1 1.22397e-5 1.51978e-6 1 1.27514e-5 9.03935e-7 1 1.25838e-5 2.97581e-7 1 0 -3.69442e-5 1 -0.8185603 -0.5744206 0 -0.8180468 -0.5751489 0.001803815 -0.8191511 -0.5735777 5.35274e-4 -0.8222003 -0.5691689 0.005785465 -0.8179109 -0.5753419 0.001862525 -0.8191519 -0.5735756 -0.001080513 3.53419e-5 0 -1 0.5735608 -0.819163 1.41118e-5 0.5735886 -0.8191435 0 0.5735752 -0.819153 2.67846e-5 0.5734919 -0.8192112 -4.88435e-5 0.5725765 -0.8198514 0 0.5735851 -0.819146 0 -0.8191516 -0.5735771 0 -0.8191521 -0.5735765 0 -1.46412e-6 0 1 -2.17615e-6 0 1 4.84583e-6 0 1 -3.3567e-6 0 1 3.29088e-6 0 1 -0.9993909 -0.03489875 1.78008e-4 -0.9993893 -0.03494453 0 0.999391 -0.03489643 2.75773e-6 0.9993909 -0.03490048 2.50031e-6 0.9993907 -0.03490418 0 0.999391 -0.03489673 0 0.9993907 -0.03490453 3.98053e-4 0.9993898 -0.03493028 2.50386e-4 0.5735881 -0.8191439 6.13485e-5 0.57358 -0.8191497 0 0.5735818 -0.8191484 0 0.5735781 -0.8191509 1.51513e-4 0.5735774 -0.8191515 6.60332e-5 0.0106678 -0.01477807 0.999834 0.01000618 -0.01557689 0.9998287 0.009877681 -0.01410317 0.9998518 0.00997883 -0.01440298 0.9998465 0.01061159 -0.0151537 0.9998289 0 -1 -5.08213e-7 0 -1 -1.35439e-6 0 -1 -1.99072e-7 0 -1 1.39216e-6 0 -1 -6.77499e-7 0 -1 -3.97683e-7 0 -1 -5.40625e-7 0 -1 5.68997e-7 0 -1 -1.28425e-6 0 -1 -3.38353e-7 0 -1 1.69223e-7 0 -1 -9.94284e-7 0 -1 3.38811e-7 0 -1 6.77048e-7 0 -1 1.98959e-7 0 -1 6.66339e-7 0 -1 2.04064e-7 0 -1 -1.69327e-7 0 -1 -1.69355e-7 0 -1 -5.97651e-7 0 -1 1.69329e-7 2.16617e-5 -1 -3.63873e-5 0 -1 2.3786e-6 0 -1 1.59073e-6 0 -1 3.38524e-7 0 -1 3.3878e-7 0 -1 -1.9907e-7 2.64642e-5 -1 -3.71604e-5 0 -1 -1.32386e-6 0 -1 -1.69068e-7 0 -1 -1.98919e-7 0 -1 -1.9888e-7 4.69971e-6 -1 -3.78675e-5 1.08071e-5 -1 -3.62844e-5 -5.46162e-7 -1 -3.15287e-5 0 -1 3.38248e-7 0 -1 -1.69401e-7 1.40564e-5 -1 -3.59455e-5 7.72862e-6 -1 -3.69491e-5 1.76148e-5 -1 -3.59893e-5 1.60725e-6 -1 -3.85835e-5 2.63563e-4 -1 1.71618e-7 2.64375e-4 -1 -8.16241e-7 2.62085e-4 -1 -3.59032e-7 6.1298e-4 -0.9999998 9.65593e-5 2.99678e-4 -1 -1.18558e-4 -4.63418e-4 -0.9999998 -3.07684e-4 3.08233e-4 -1 -1.14986e-4 2.63543e-4 -1 0 -0.0413202 0 0.999146 -0.1237004 0 0.9923197 -0.2052225 0 0.9787154 -0.2853367 0 0.9584273 -0.363504 0 0.9315927 -0.4362356 0 0.8998325 -0.4392045 -0.00152105 0.8983858 -0.5118815 -0.003151953 0.8590503 -0.5058858 -9.95096e-5 0.8626006 -0.5810742 -0.004015266 0.8138406 -0.5724917 1.16659e-4 0.8199107 -0.6462873 -0.005106747 0.7630772 -0.6668363 0.001783847 0.7452021 -0.625746 0.001439154 0.7800256 -0.7103934 -0.003330409 0.703797 -0.7071132 -9.47612e-4 0.7070997 -0.7555794 4.76968e-5 0.6550571 -0.7630782 -0.00446093 0.6462907 -0.813829 -0.007105231 0.581061 -0.7906991 0.002189755 0.6122012 -0.861917 -0.005863904 0.5070157 -0.8590558 -0.002914309 0.5118737 -0.8871644 0.001786887 0.4614503 -0.8983641 -0.007598698 0.4391859 -0.915311 0.002577841 0.4027397 -0.9315599 -0.007973432 0.3635007 -0.9583987 -0.007755696 0.2853274 -0.9630226 3.42033e-4 0.2694206 -0.9786879 -0.007766306 0.205207 -0.9758256 -3.4051e-4 0.2185508 -0.9922819 -0.008861362 0.123686 -0.9890056 0.002894699 0.1478502 -0.9971098 0.003760576 0.07588183 -0.9991076 -0.008749306 0.04132318 -0.9991074 -0.008772313 -0.04132384 -0.9922867 -0.008282601 -0.1236872 -0.9766352 -0.001447439 -0.2148991 -0.978692 -0.007160484 -0.2052095 -0.9583953 -0.008268237 -0.2853248 -0.9644288 0.001303136 -0.2643399 -0.9315604 -0.008186101 -0.3634945 -0.9435096 0.003832638 -0.3313232 -0.8851292 0.006066739 -0.4653061 -0.8983641 -0.006956934 -0.4391964 -0.8590313 -0.007910728 -0.511862 -0.8138209 -0.007317841 -0.5810698 -0.7630811 -0.003461599 -0.6462935 -0.7588374 -6.09709e-4 -0.6512799 -0.7071215 -1.93627e-4 -0.7070921 -0.7122007 -0.004043996 -0.7019643 -0.6255327 0.001777231 -0.780196 -0.6685888 0.001981079 -0.7436297 -0.6462833 -0.005154967 -0.7630802 -0.5810906 -0.003246903 -0.8138325 -0.5804855 -0.002955138 -0.8142652 -0.5367969 0.001771807 -0.8437097 -0.511871 -0.005122244 -0.859047 -0.4392083 -0.002566933 -0.8983817 -0.3634861 0 -0.9315996 -0.2853336 0 -0.9584283 -0.2052366 0 -0.9787124 -0.1236829 0 -0.9923218 -0.04131263 0 -0.9991463 0.04132318 0 -0.9991459 0.1236984 0 -0.9923199 0.2052232 0 -0.9787152 0.2853345 0 -0.958428 0.3634977 0 -0.9315951 0.4392036 0 -0.8983876 0.5118905 0 -0.8590508 0.5810861 0 -0.8138421 0.6462871 0 -0.7630945 0.7071088 0 -0.7071049 0.7630797 0 -0.6463044 0.8138469 0 -0.5810794 0.8590581 0 -0.5118783 0.8983861 0 -0.4392067 0.9315918 0 -0.3635066 0.9584284 0 -0.2853333 0.9787173 0 -0.2052134 0.9923212 0 -0.1236877 0.9991457 0 -0.04132682 0.9991457 0 0.04132747 0.9923215 0 0.1236858 0.9787173 0 0.2052134 0.9584271 0 0.2853376 0.9315918 0 0.3635066 0.8983861 0 0.4392067 0.8590581 0 0.5118783 0.8138523 0 0.5810719 0.7630863 0 0.6462966 0.7071088 0 0.7071049 0.6462963 0 0.7630867 0.5810756 0 0.8138496 0.5118788 0 0.8590577 0.4391908 0 0.8983939 0.3635115 0 0.9315897 0.2853345 0 0.958428 0.2052081 0 0.9787184 0.1236829 0 0.9923218 0.04132318 0 0.9991459 0.1236984 0 0.9923199 0.2052233 0 0.9787152 0.2853344 0 0.9584281 0.3635113 0 0.9315898 0.4392036 0 0.8983876 0.5118905 0 0.8590508 0.7630797 0 0.6463044 0.8138469 0 0.5810794 0.9923212 0 0.1236877 0.9991457 0 0.04132682 0.9991457 0 -0.04132747 0.992321 0 -0.1236897 0.8138523 0 -0.5810719 0.7630863 0 -0.6462966 0.5118788 0 -0.8590577 0.4391908 0 -0.8983939 0.3634976 0 -0.9315952 0.2853344 0 -0.9584281 0.2052385 0 -0.978712 0.1236829 0 -0.9923218 -0.04132318 0 -0.9991459 -0.1236984 0 -0.9923199 -0.2052275 0 -0.9787144 -0.2853308 0 -0.9584292 -0.3635038 0 -0.9315928 -0.4335478 0 -0.9011306 -0.4885829 0.00151056 -0.8725162 -0.79469 0.001971662 -0.6070125 -0.8387781 0.004903197 -0.5444515 -0.9187785 0.002268135 -0.3947671 -0.989733 0.002453863 -0.1429083 -0.9979082 0.003160119 -0.06456947 -0.9999452 0.003599047 0.009830653 -0.9411763 0.003191888 0.337901 -0.8288478 0.001364231 0.5594727 -0.3635137 0 0.9315888 -0.2853336 0 0.9584283 -0.2052063 0 0.9787188 -0.1236829 0 0.9923218 -0.04132843 0 0.9991456 0 -1 2.08559e-6 0 -1 4.15717e-6 0 -1 -3.03098e-7 0 -1 1.61888e-6 0 -1 -6.01723e-7 0 -1 -2.42491e-6 0 -1 2.40686e-7 0 -1 -1.74297e-7 0 -1 -5.34428e-7 0 -1 -1.24434e-5 0 -1 -3.4858e-7 0 -1 3.34018e-7 0 -1 0 0 -1 1.21331e-6 0 -1 2.44868e-7 0 -1 0 0 -1 -7.09316e-7 0 -1 0 0 -1 -2.37955e-7 0 -1 -2.87813e-6 0 -1 3.02542e-7 0 -1 -1.98346e-7 0 -1 0 0 -1 -1.41031e-7 0 -1 -1.21336e-6 0 -1 0 0 -1 3.66644e-6 0 -1 2.98641e-7 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 -1.69995e-7 0 -1 1.82814e-7 0 -1 8.55754e-7 -0.4385417 -7.47016e-5 0.8987109 -0.4384136 -6.35161e-6 0.8987735 -0.4383616 -8.7978e-6 0.8987987 -0.4383574 -2.14473e-5 0.8988009 -0.4383926 6.02935e-6 0.8987836 -0.4383921 -4.54286e-6 0.8987838 -0.4383863 5.75806e-6 0.8987867 -0.4384 -2.3637e-5 0.89878 -0.438367 -1.11629e-5 0.8987961 -0.4383221 8.31862e-6 0.8988181 -0.4383445 -2.76822e-5 0.8988071 -0.4385366 -2.60511e-5 0.8987134 -0.4383779 1.44765e-5 0.8987908 -0.4528591 -5.68456e-4 0.891582 -0.4383597 -4.05829e-6 0.8987997 -0.4383612 1.00568e-5 0.898799 -0.4384693 0 0.8987461 -0.438372 1.91114e-7 0.8987938 -0.4383774 -1.49573e-5 0.8987911 -0.4383717 -5.02286e-5 0.8987939 -0.4383624 -2.95891e-5 0.8987984 -0.4383608 -9.19597e-6 0.8987992 -0.4383862 -5.69333e-6 0.8987867 -0.4383529 5.29696e-5 0.898803 -0.438363 4.01402e-6 0.8987981 -0.4383332 9.23604e-5 0.8988126 -0.4383757 3.03318e-5 0.8987919 -0.4383695 0 0.8987949 -0.4383677 -7.75684e-5 0.8987959 -0.4383539 3.73004e-6 0.8988025 -0.4383698 -5.00527e-5 0.8987947 -0.4521996 0.002856254 0.8919122 -0.4382511 0 0.8988527 -0.4383625 -1.6625e-5 0.8987982 -0.4384132 -2.59553e-5 0.8987736 5.47462e-4 -0.9945145 0.1045977 1.40562e-4 -0.9945049 0.1046912 2.6202e-4 -1 2.26339e-7 2.64323e-4 -1 -2.27772e-7 2.65994e-4 -1 0 2.5926e-4 -1 1.59549e-6 2.63513e-4 -1 0 3.25084e-4 -1 1.40086e-7 2.63543e-4 -1 -2.2979e-7 2.67876e-4 -1 -4.49513e-6 2.64361e-4 -1 -2.27717e-7 2.60886e-4 -1 -5.01201e-6 2.65929e-4 -1 -1.38687e-6 1.67241e-4 -1 4.0913e-5 0.001607477 -0.9999988 3.40203e-5 2.63423e-4 -1 0 1.60648e-4 -1 1.32197e-5 1.55866e-4 -1 -4.81808e-5 1.58699e-4 -1 -2.81875e-5 2.55986e-4 -0.999994 0.003471314 0.9283677 -4.88748e-4 -0.3716628 0.9954695 0 -0.09508204 0.9819222 0 0.1892853 0.8888409 0 0.4582162 0.7237185 0 0.6900953 0.5000222 0 0.8660127 0.235759 0 0.9718117 -0.04760462 0 0.9988663 -0.3271221 0 0.9449822 -0.5800788 0 0.8145605 -0.7860689 0 0.618139 -0.7860463 1.37137e-6 0.6181678 -0.5800399 0 0.8145881 -0.3270438 0 0.9450093 -0.04756456 0 0.9988682 0.2358053 0 0.9718003 0.5000048 0 0.8660227 0.7237164 0 0.6900976 0.8888427 0 0.4582127 0.9819225 0 0.1892837 0.9954699 0 -0.09507805 0.9320045 0 -0.3624466 -0.8660264 -3.37137e-6 0.4999983 -0.8660266 -2.60695e-6 0.499998 -0.8660221 -6.80451e-7 0.500006 -0.8665677 5.28935e-4 0.4990595 -0.8660255 0 0.4999999 0.8660215 2.29735e-6 -0.500007 0.8660258 0 -0.4999993 0.8658114 1.79429e-4 -0.5003706 0.8660751 9.84736e-5 -0.4999139 -0.9531236 -0.004580378 0.3025467 -0.9941538 -3.8107e-4 0.107973 -0.983672 5.12713e-4 -0.1799702 -0.8847473 -9.69367e-4 -0.4660701 -0.8888211 -3.76758e-4 -0.4582543 -0.7237446 -3.79294e-4 -0.6900678 -0.7266049 -6.58585e-4 -0.6870554 -0.4999749 -1.88994e-4 -0.8660399 -0.4870315 8.29585e-4 -0.8733841 -0.2357529 -0.001438617 -0.971812 -0.2143453 -1.57708e-4 -0.976758 0.04759186 2.33688e-4 -0.9988669 0.003260493 -0.00276035 -0.9999909 0.297449 -0.001029849 -0.9547372 0.3270364 0.001412987 -0.9450107 0.5800359 8.218e-5 -0.8145909 0.5726248 -5.40692e-4 -0.8198174 0.7860462 2.52454e-4 -0.6181677 0.755872 -0.002925217 -0.654713 -0.9819305 -1.445e-4 -0.1892421 -0.9954734 -0.001167237 0.09503448 -0.9283519 4.87161e-4 0.3717025 0 -1 -1.84254e-6 0 -1 -2.57538e-6 0 -1 -6.2685e-6 0 -1 7.79095e-6 0 -1 4.37599e-6 0 -1 7.68096e-6 0 -1 -2.44927e-7 0 -1 2.44927e-7 0 -1 4.14546e-6 0 -1 -7.36985e-6 0.9993909 0 -0.03489786 0.9777796 0 -0.2096356 0.7372804 0 -0.6755869 0.3600292 0 -0.932941 0.3600067 0 -0.9329497 -0.3599926 0 -0.9329553 -0.360015 0 -0.9329465 -0.737282 0 -0.6755852 0 -1 -8.42713e-7 -0.9993909 -3.17251e-4 -0.03489667 -0.9993863 0 -0.03503048 -0.9777829 0 -0.2096204 0.302519 0 0.9531435 0.3668635 0 0.9302748 0.429482 0 0.9030755 0.4901136 0 0.8716586 0.5484567 0 0.836179 0.6042368 0 0.7968049 0.6572113 0 0.7537065 0.7071024 0 0.7071112 0.7537207 0 0.6571949 0.7968009 0 0.6042421 0.8361864 0 0.5484455 0.8716574 0 0.4901158 0.9030768 0 0.429479 0.9302779 0 0.3668556 0.9531449 0 0.3025144 0.9715677 0 0.2367621 0.9854602 0 0.1699069 0.9947566 0 0.1022717 0.9994173 0 0.03413516 0.03414469 0 0.999417 0.1022775 0 0.994756 0.1699082 0 0.9854599 0.2365261 -0.04578119 0.9705461 0.2638602 0 0.9645609 0.2639012 0 0.9645497 0.2307766 0 0.9730069 0.2367706 7.05167e-4 0.9715654 0.1659103 0 0.9861409 0.09440225 0 0.9955341 0.1020882 -0.05975043 0.9929794 0.03412389 0 0.9994177 0.03414767 0 0.9994169 0.09664583 0.002127707 0.9953166 0.1697675 0.04278421 0.9845551 0.2307744 0 0.9730073 0.1022645 0 0.9947573 0.03411585 0 0.9994179 0.9947564 0 0.1022727 0.9854598 0 0.1699085 0.9715666 0 0.2367665 0.9531458 0 0.3025116 0.9302805 0 0.366849 0.9030787 0 0.4294753 0.8716527 0 0.4901241 0.8361805 0 0.5484544 0.7537123 0 0.6572046 0.7071121 0 0.7071015 0.6572002 0 0.7537162 0.6042243 0 0.7968143 0.4294661 0 0.9030831 0.3668466 0 0.9302815 3.31591e-6 -1 -9.53183e-6 0 -1 -8.9771e-7 0 -1 -5.57065e-7 -1.73511e-5 -1 9.43849e-7 -1.58961e-6 -1 1.53052e-6 0 -1 1.58454e-6 2.51715e-6 -1 -5.66369e-7 0 1 -6.40009e-7 -0.2135027 0 -0.9769425 -0.1425079 0 -0.9897937 -0.07144743 0 -0.9974444 0.07144743 0 -0.9974444 0.1424855 0 -0.9897969 0.2128393 0 -0.9770873 0.142508 0 -0.9897937 -0.1424853 0 -0.989797 -0.2128612 -5.82577e-4 -0.9770823 0 5.00488e-4 1 -8.44172e-5 0.00165975 0.9999986 -0.9324799 0 0.3612221 -0.9448873 0 0.3273961 -0.9397885 0.003724038 0.3417364 -0.9619589 0 0.2731944 -0.980055 0 0.1987262 -0.9923747 0 0.1232578 -0.9912163 -0.003141283 0.1322141 -0.9920441 0.003088235 0.1258531 -0.9791259 0.002297103 0.2032422 -0.9324724 0 0.3612413 0.9961252 0 0.08794683 0.9881553 -0.004650056 0.1533865 0.9904259 0.004971385 0.137956 0.991398 0 0.1308819 0.978653 0.005033671 0.2054582 0.9594148 0 0.2819986 0.9356636 0.00680077 0.3528278 0.9273963 -0.002988815 0.3740686 0.9252854 -4.43157e-4 0.3792713 0.9551864 -0.005648314 0.2959512 0.9759125 0 0.2181623 0.9961251 0 0.08794915 0 1 -1.14696e-6 0 1 3.92684e-6 0 1 2.83e-6 0 1 -1.75893e-6 0 1 -1.03248e-6 0 1 -7.94984e-7 -6.24141e-6 1 1.77138e-5 0 1 0 -5.52255e-7 1 1.85732e-7 0 1 6.47061e-7 0 1 1.37583e-7 0 1 0 1.66092e-6 1 -8.36588e-6 -2.19999e-7 1 2.2244e-6 -0.8918555 0 0.4523204 -0.8025104 0 0.5966382 -0.682519 5.6715e-4 0.7308676 -0.515654 0 0.856797 -0.3369727 0.00137782 0.9415135 -0.3481706 0 0.9374312 -0.5202221 -5.67899e-4 0.8540309 -0.6863575 0 0.7272644 -0.8025307 0 0.5966108 0.2232099 0 0.9747704 0.3849177 0 0.922951 0.544128 5.6566e-4 0.839002 0.7066794 0 0.7075339 0.8309341 0.001189827 0.5563696 0.8252563 0 0.5647585 0.702887 -5.6718e-4 0.7113013 0.5396847 0 0.8418674 0.3848691 0 0.9229713 0.2233181 0 0.9747456 -0.1113215 0 0.9937846 -0.03513854 0 0.9993826 0.03513854 0 0.9993826 0.1051916 0 0.994452 0.1052256 0 0.9944484 0.03513854 0 0.9993825 -0.03513854 0 0.9993825 -0.1155312 -0.001507401 0.9933028 0 1 2.23682e-7 0 1 -1.58514e-7 0 1 -2.7841e-7 0 1 -5.03636e-7 0 1 3.02016e-7 0 1 5.72586e-7 0 1 3.29126e-7 0 1 -2.23688e-7 0 1 -3.02017e-7 0 1 5.03623e-7 0 1 -5.72587e-7 -0.8260562 8.08483e-7 0.5635879 -0.8260576 1.02068e-6 0.5635856 -0.8260534 -8.51316e-7 0.5635921 -0.8260788 -9.27222e-5 0.5635546 -0.8261933 -1.51921e-4 0.5633867 -0.8260599 -2.49467e-7 0.5635823 -0.8260501 2.86549e-7 0.5635969 -0.8260404 -5.62781e-5 0.5636109 -0.8260551 0 0.5635893 -0.8260556 1.68599e-6 0.5635887 -0.8260564 1.08853e-6 0.5635877 -0.826065 5.42671e-6 0.5635748 -0.8260548 2.62852e-6 0.5635901 -0.8260524 3.25508e-6 0.5635932 -0.8260532 -3.2976e-6 0.5635923 -0.8260524 3.87716e-6 0.5635935 -0.8260638 -4.91855e-6 0.5635768 -0.8260506 -1.33674e-5 0.5635962 -0.826058 2.85187e-7 0.5635852 -0.8260627 -9.49517e-6 0.5635783 -0.8260561 -6.86025e-6 0.5635879 -0.8260633 1.47009e-5 0.5635776 -0.8260534 1.95043e-6 0.5635921 -0.8260496 -1.18651e-5 0.5635976 -0.8260964 -4.85578e-5 0.5635289 -0.8260675 1.77284e-5 0.5635715 -0.8260349 -5.83735e-5 0.563619 -0.826064 9.54969e-6 0.5635764 -0.8260635 1.90776e-5 0.5635773 -0.8260561 -2.54567e-6 0.5635882 -0.8260636 1.40957e-5 0.563577 -0.8260571 0 0.5635865 -0.8260737 1.31793e-5 0.5635623 -0.826054 1.9718e-6 0.5635912 -0.8260512 1.44771e-5 0.5635951 -0.8260799 7.57515e-6 0.5635532 -0.8260803 -1.61951e-5 0.5635525 -0.8260569 -4.40529e-6 0.5635868 -0.8260767 -1.33928e-5 0.5635579 -0.826049 2.2693e-5 0.5635984 -0.8260831 9.48593e-6 0.5635485 -0.8260626 6.91706e-6 0.5635784 -0.8260693 -4.59131e-5 0.5635686 -0.8260537 -2.20898e-6 0.5635914 -0.8260511 8.2737e-6 0.5635951 -0.8260882 7.2606e-6 0.5635409 -0.8260484 -3.35805e-5 0.5635991 -0.8260506 3.26353e-5 0.563596 -0.8260637 -1.7402e-5 0.5635769 -0.8260397 -1.43513e-6 0.563612 -0.8261203 1.81492e-4 0.5634939 -0.8255683 0.002134621 0.5642983 -0.6691401 -1.28175e-6 0.7431364 -0.6691437 9.65253e-7 0.7431331 -0.6691272 1.02733e-6 0.7431479 -0.6691389 -5.90066e-7 0.7431374 -0.6691184 -3.6739e-7 0.7431558 -0.6691333 -2.03403e-7 0.7431425 -0.6691263 -4.76097e-7 0.7431487 -0.6691242 3.76169e-7 0.7431506 -0.6691364 5.08377e-6 0.7431396 -0.6691343 0 0.7431415 -0.6690151 -3.89946e-5 0.7432488 -0.6691284 -1.73717e-6 0.7431468 -0.6688843 -2.0975e-4 0.7433665 -0.6691175 6.08829e-5 0.7431567 -0.6692835 -1.84328e-6 0.7430072 -0.6694691 1.98521e-4 0.74284 -0.422622 -4.01368e-7 0.9063061 -0.4226195 -5.11923e-7 0.9063073 -0.4226108 1.8306e-6 0.9063114 -0.4226166 -1.73911e-7 0.9063085 -0.4226141 -3.63187e-6 0.9063098 -0.4226167 9.78198e-7 0.9063085 -0.4226167 1.31196e-6 0.9063085 -0.4226178 2.31109e-6 0.9063081 -0.4226319 1.48362e-6 0.9063016 -0.4226267 9.08135e-7 0.9063039 -0.4226269 -3.63365e-6 0.9063039 -0.4226174 -1.78957e-6 0.9063083 -0.4226086 -3.4655e-6 0.9063124 -0.4226162 4.64641e-6 0.9063088 -0.4226376 -1.19367e-5 0.9062988 -0.4226316 1.15432e-6 0.9063016 -0.4226105 -8.8852e-7 0.9063114 -0.4226204 6.05878e-7 0.9063069 -0.4226056 5.04817e-7 0.9063137 -0.422605 5.81709e-6 0.9063141 -0.4226114 -3.03434e-7 0.906311 -0.4226114 2.84576e-7 0.9063111 -0.4226136 1.88625e-6 0.90631 -0.4226235 1.4977e-6 0.9063054 -0.4226163 5.05185e-7 0.9063088 -0.4226179 -1.78522e-6 0.9063081 -0.4226143 5.53708e-6 0.9063097 -0.4226211 -1.62093e-6 0.9063066 -0.4226285 -2.02421e-7 0.9063031 -0.422616 8.07468e-7 0.906309 -0.4226236 -2.13346e-6 0.9063053 -0.4226271 6.12877e-6 0.9063037 -0.4226086 -5.48302e-6 0.9063123 -0.42262 1.21168e-6 0.906307 -0.4226111 6.03539e-6 0.9063112 -0.4226115 0 0.906311 -0.4226061 -7.39753e-6 0.9063135 -0.422616 5.07509e-6 0.9063089 -0.4226278 -6.91653e-6 0.9063035 -0.422632 1.19758e-5 0.9063014 -0.4226231 -8.6791e-6 0.9063056 -0.4226088 2.82587e-6 0.9063122 -0.4226213 3.73459e-6 0.9063064 -0.4226151 -8.94855e-7 0.9063094 -0.4226323 -8.93016e-6 0.9063013 -0.4226126 -9.59165e-6 0.9063104 -0.4226161 4.8437e-6 0.9063088 -0.422451 1.62668e-4 0.9063858 -0.4226064 8.89568e-6 0.9063133 -0.422612 -7.96341e-6 0.9063107 -0.4229813 -2.17248e-4 0.9061385 -0.4226247 -3.24362e-6 0.9063048 -0.4238944 1.02617e-4 0.9057116 -0.4226117 6.37547e-6 0.906311 -0.4226137 -6.93385e-6 0.90631 -0.4226228 8.29924e-6 0.9063058 -0.4226158 -2.52441e-6 0.906309 -0.4226148 -2.56699e-6 0.9063094 -0.4226239 3.43281e-6 0.9063053 -0.4226168 -7.55054e-7 0.9063086 -0.4226179 -3.64534e-6 0.9063081 -0.4226214 1.09663e-5 0.9063064 -0.4226169 -2.83857e-6 0.9063084 -0.4226187 6.05406e-7 0.9063077 -0.4226151 1.61696e-6 0.9063093 -0.422621 2.42843e-6 0.9063065 -0.4226121 6.23632e-6 0.9063107 -0.422618 4.34731e-6 0.9063079 -0.4226202 -4.86352e-6 0.9063069 -0.4226158 -9.23798e-6 0.906309 -0.422618 -6.06255e-6 0.9063079 -0.4226174 -3.13197e-6 0.9063083 -0.4226126 8.12981e-6 0.9063105 -0.4226191 6.51587e-6 0.9063075 -0.4226198 4.15886e-6 0.9063071 -0.4226194 -2.98371e-6 0.9063073 -0.4226191 3.12962e-6 0.9063075 -0.4226207 -5.58999e-6 0.9063067 -0.4226183 7.82341e-6 0.9063079 -0.4226126 -9.68961e-6 0.9063105 -0.422619 -8.08385e-6 0.9063075 -0.4226175 6.09724e-6 0.9063082 -0.4226162 -8.51427e-6 0.9063088 -0.4226169 7.59336e-6 0.9063085 -0.4226189 5.11974e-6 0.9063076 -0.4226188 1.89077e-6 0.9063076 -0.4226204 2.45491e-6 0.9063069 -0.4226169 -8.09951e-7 0.9063084 -0.4226183 4.92294e-7 0.9063079 -0.4226191 -8.07587e-6 0.9063075 -0.4226159 0 0.906309 -0.4229906 -4.04797e-5 0.9061341 -0.6691308 3.5633e-7 0.7431447 -0.6691786 2.50293e-6 0.7431016 -0.6691296 1.82625e-6 0.7431458 -0.6694864 1.75463e-4 0.7428243 -0.6691304 1.01636e-6 0.7431451 -0.6691277 2.02434e-7 0.7431476 -0.6691301 -3.31041e-7 0.7431453 -0.669131 1.67463e-6 0.7431445 -0.6691344 -4.96533e-7 0.7431414 -0.6691295 -2.91495e-7 0.7431459 -0.6691294 1.81892e-6 0.743146 -0.6691308 -1.28071e-7 0.7431448 -0.6691272 4.48385e-7 0.7431479 -0.6692327 -1.37275e-5 0.7430529 -0.6691996 4.4732e-6 0.7430827 0.03739416 0.9993004 -6.81778e-4 0.05445629 0.998516 6.30939e-4 -0.03739416 0.9993006 -2.11244e-4 -0.02511399 0.9996845 5.60005e-4 -0.1119577 0.993713 -2.01345e-4 -0.09971928 0.9950155 5.35425e-4 -0.1859143 0.982566 -1.92438e-4 -0.1737888 0.9847828 5.13169e-4 -0.2588245 0.9659245 -1.8444e-4 -0.2468559 0.9690521 4.94141e-4 -0.3302751 0.9438848 -1.77585e-4 -0.3185512 0.9479056 4.75971e-4 -0.3998914 0.9165626 -1.70918e-4 -0.3911606 0.9203224 3.11672e-4 -0.4672694 0.884115 1.26488e-4 -0.4664654 0.8845395 1.66262e-4 -0.5320331 0.8467237 -1.58375e-4 -0.5200256 0.8541507 4.72566e-4 -0.5938203 0.8045977 -1.7108e-4 -0.5836484 0.8120064 4.05754e-4 -0.6522876 0.7579716 -1.45249e-4 -0.6428751 0.7659709 3.88244e-4 -0.7071064 0.7071071 -1.39454e-4 -0.6982859 0.715819 3.7464e-4 -0.7579717 0.6522875 -1.34484e-4 -0.7498019 0.6616624 3.6274e-4 -0.8045984 0.5938194 -1.30128e-4 -0.797128 0.6038103 3.52686e-4 -0.846723 0.5320341 -1.26511e-4 -0.8400001 0.5425862 3.44073e-4 -0.8841159 0.4672676 -1.23314e-4 -0.8781808 0.478329 3.36882e-4 -0.9165621 0.3998923 -1.20664e-4 -0.9114549 0.4114 3.31137e-4 -0.9438847 0.3302752 -1.18591e-4 -0.9396372 0.3421722 3.26417e-4 -0.9659248 0.2588231 -1.16819e-4 -0.9625669 0.2710439 3.22943e-4 -0.9825661 0.1859139 -1.15436e-4 -0.9801282 0.1983651 3.19713e-4 -0.9937132 0.111957 -1.14251e-4 -0.9922083 0.1245904 3.18327e-4 -0.9993008 0.03739196 -1.13743e-4 -0.9989392 0.04604929 1.79194e-4 -0.9989392 -0.04604887 1.79194e-4 -0.9922083 -0.1245908 3.18326e-4 -0.9801283 -0.1983644 3.19712e-4 -0.9625669 -0.2710441 3.22928e-4 -0.9396373 -0.3421719 3.26468e-4 -0.9114537 -0.4114027 3.31176e-4 -0.8781808 -0.4783288 3.36852e-4 -0.8399993 -0.5425876 3.44095e-4 -0.7971274 -0.6038111 3.52694e-4 -0.7498003 -0.6616641 3.62773e-4 -0.6982871 -0.7158177 3.74695e-4 -0.6428751 -0.7659709 3.88171e-4 -0.5838727 -0.8118452 4.04039e-4 -0.5214976 -0.8532528 4.23227e-4 -0.4670113 -0.8842514 1.75717e-4 -0.467269 -0.8841152 1.861e-4 -0.3913753 -0.9202312 2.999e-4 -0.3185515 -0.9479054 4.75862e-4 -0.2468556 -0.9690521 4.94265e-4 -0.1737889 -0.9847829 5.13128e-4 -0.09972071 -0.9950153 5.35308e-4 -0.02424371 -0.999706 5.67527e-4 0.06034725 -0.9981771 8.73676e-4 0.1291306 -0.9916272 9.66904e-4 0.1981148 -0.9801787 6.33714e-4 0.2708897 -0.9626103 6.56653e-4 0.3420556 -0.9396795 6.74569e-4 0.4113242 -0.9114889 6.93225e-4 0.4782865 -0.8782036 7.11714e-4 0.5425829 -0.840002 7.31369e-4 0.6038443 -0.797102 7.5104e-4 0.6617314 -0.7497407 7.70798e-4 0.7159195 -0.6981825 7.9029e-4 0.7661014 -0.6427193 8.09303e-4 0.8119998 -0.5836573 8.27901e-4 0.8533562 -0.5213276 8.4539e-4 0.8899384 -0.4560799 8.61681e-4 0.921546 -0.3882684 8.77388e-4 0.9479948 -0.3182845 8.90492e-4 0.9691338 -0.2465339 9.02122e-4 0.9848499 -0.1734068 9.09252e-4 0.9948477 -0.1013779 8.86203e-4 0.9993004 -0.03739428 7.79607e-4 0.9987572 -0.04984188 0 0.9997925 0.02037125 -4.24797e-4 0.9993004 0.03739231 7.49145e-4 0.9937129 0.1119586 -3.29847e-4 0.9950586 0.09928548 9.16017e-4 0.9825664 0.1859121 -3.2691e-4 0.9848499 0.1734066 9.09226e-4 0.9659244 0.2588246 -3.24755e-4 0.9691342 0.2465322 9.02074e-4 0.9438849 0.3302747 -3.22358e-4 0.9479955 0.3182828 8.90588e-4 0.9165623 0.399892 -3.18358e-4 0.9215468 0.3882665 8.77329e-4 0.884116 0.4672675 -3.13616e-4 0.8899387 0.4560793 8.6169e-4 0.846724 0.5320324 -3.08381e-4 0.8533554 0.5213291 8.4535e-4 0.8045983 0.5938193 -3.02544e-4 0.8120011 0.5836555 8.27816e-4 0.7579721 0.652287 -2.96312e-4 0.7661013 0.6427195 8.09264e-4 0.7071059 0.7071077 -2.89686e-4 0.7159198 0.6981821 7.90299e-4 0.6522867 0.7579725 -2.82975e-4 0.6617311 0.7497408 7.70621e-4 0.59382 0.8045979 -2.76029e-4 0.6038449 0.7971014 7.50969e-4 0.5320326 0.8467239 -2.69126e-4 0.5425826 0.8400021 7.31266e-4 0.4672689 0.8841153 -2.62086e-4 0.4782873 0.8782032 7.11853e-4 0.3998918 0.9165623 -2.5504e-4 0.4113233 0.9114894 6.92962e-4 0.3302747 0.9438849 -2.48455e-4 0.3420556 0.9396795 6.74572e-4 0.2588245 0.9659245 -2.41858e-4 0.2708902 0.9626101 6.5673e-4 0.1859143 0.982566 -2.35302e-4 0.1981148 0.9801787 6.3368e-4 0.1119577 0.993713 -2.03702e-4 0.1331763 0.9910917 0.001242935 0.993713 -0.1119581 0 0.9825664 -0.185912 -3.26922e-4 0.9659243 -0.2588245 -3.24742e-4 0.9438855 -0.3302729 -3.22418e-4 0.9165632 -0.3998898 -3.18345e-4 0.884116 -0.4672675 -3.13624e-4 0.846724 -0.5320324 -3.08406e-4 0.8045985 -0.5938192 -3.02519e-4 0.7579725 -0.6522866 -2.96393e-4 0.707107 -0.7071065 -2.89734e-4 0.6522865 -0.7579725 -2.83146e-4 0.5938199 -0.804598 -2.76089e-4 0.5320332 -0.8467236 -2.692e-4 0.4672689 -0.8841153 -2.62072e-4 0.3998917 -0.9165624 -2.55235e-4 0.3302748 -0.9438848 -2.48292e-4 0.2588242 -0.9659245 -2.41937e-4 0.1859145 -0.9825659 -2.35353e-4 0.1119577 -0.993713 -2.03727e-4 0.03739416 -0.9993002 -8.97742e-4 -0.03739416 -0.9993006 -2.96697e-4 -0.1119577 -0.993713 -2.01212e-4 -0.1859143 -0.982566 -1.92396e-4 -0.2588244 -0.9659245 -1.84561e-4 -0.3302751 -0.9438848 -1.77546e-4 -0.3998914 -0.9165626 -1.70899e-4 -0.5320324 -0.846724 -1.29873e-4 -0.5938194 -0.8045983 -1.51961e-4 -0.6522867 -0.7579724 -1.45225e-4 -0.7071067 -0.707107 -1.39477e-4 -0.7579724 -0.6522866 -1.34536e-4 -0.8045985 -0.5938194 -1.30164e-4 -0.8467245 -0.5320318 -1.26518e-4 -0.8841159 -0.4672678 -1.23311e-4 -0.9165627 -0.399891 -1.20687e-4 -0.9438848 -0.3302751 -1.18542e-4 -0.9659248 -0.2588232 -1.16839e-4 -0.9825661 -0.1859139 -1.15413e-4 -0.9937132 -0.111957 -1.14251e-4 -0.9993008 -0.03739196 -1.13743e-4 0.6114519 -0.7912816 1.78236e-4 0.563501 -0.8261154 3.79268e-5 0.5602492 -0.8283241 -1.95724e-4 0.5128201 -0.858496 -3.93577e-4 0.5031552 -0.8641961 3.16697e-4 0.6072067 -0.7945439 -1.55881e-4 0.002776741 0.9999962 1.09298e-4 0.001348495 0.9999991 5.30374e-5 6.99396e-4 0.9945109 -0.1046307 0.497696 -0.8627796 0.08894026 0.5138705 -0.8529408 0.09181016 0.5299037 -0.843439 0.08839082 0.5602068 -0.8237228 0.08745992 0.5733562 -0.814912 0.08474296 0.5904347 -0.8019826 0.09061497 0.608322 -0.7892638 0.08370822 0 -1 1.64191e-5 2.12253e-4 -1 -3.03505e-5 1.24667e-6 -1 1.97983e-6 0.5914293 -0.8063549 -0.00180751 0.5908161 -0.8068062 1.18693e-4 0.4296087 -0.9023528 0.03458315 0.4188857 -0.907917 -0.01489061 0.465515 -0.8841971 0.03861778 0.4765516 -0.8790781 -0.0109682 0.5048851 -0.8627437 0.02764874 0.5014573 -0.8651694 0.004758596 0.5363829 -0.8438547 -0.01423734 0.5448697 -0.8378505 0.0335195 0.5737008 -0.819037 -0.006775677 0.5790961 -0.8151237 0.01487189 0.5956587 -0.8030182 -0.01877385 0.6157719 -0.7878633 0.009826481 0.6164744 -0.7873602 0.004828095 0.443479 -0.8961921 -0.01289159 -0.762058 -0.6472147 0.01951563 -2.09692e-5 -0.01745349 0.9998478 1.18761e-5 -0.017452 0.9998477 -0.02016246 -0.01677787 0.999656 -6.08972e-5 -0.01746487 0.9998476 2.01067e-5 -0.01745194 0.9998477 1.4086e-5 -0.01745051 0.9998478 0 -0.01745343 0.9998477 0 -0.01745301 0.9998477 -1.92457e-6 -0.01745253 0.9998478 1.08971e-4 -0.01740998 0.9998484 0 -0.01745188 0.9998478 0 -0.0174483 0.9998478 6.44866e-6 -0.0174517 0.9998477 -1.44901e-6 -0.017452 0.9998477 -8.38194e-6 -0.01745706 0.9998477 -0.9986309 -0.05231159 2.93684e-4 -0.9986296 -0.05233591 0 0.4867384 -0.8735473 9.82451e-4 0.459277 -0.8882932 -6.2441e-5 0.484252 -0.8749285 -2.31699e-4 0.4550448 -0.8904686 0 0.4533714 -0.8913217 2.96219e-4 0.4886611 -0.8724733 -9.08872e-4 0.4101068 -0.9120374 -3.65076e-4 0.3580339 -0.9337087 -1.85828e-4 0.3578419 -0.9337822 -1.77236e-4 0.2875425 -0.9577679 -3.02846e-4 0.2208277 -0.9753127 -4.89705e-4 0.1558634 -0.9877785 -5.11561e-4 0.09018081 -0.9959253 -5.37255e-4 0.02366763 -0.9997198 -5.69429e-4 -0.0471633 -0.998887 -7.62948e-4 -0.107492 -0.9942058 -5.79479e-4 -0.146853 -0.9891584 -2.87885e-4 -0.1747096 -0.98462 4.12148e-4 -0.1787051 -0.9839028 1.85559e-4 -0.239389 -0.9709234 -8.27757e-4 -0.3022212 -0.9532375 -7.70982e-4 -0.3646182 -0.9311568 -8.00037e-4 -0.4254172 -0.9049969 -8.29538e-4 -0.4821829 -0.8760706 -4.38181e-4 -0.4647753 -0.8854287 3.26777e-4 -0.4900897 -0.871672 -1.45282e-4 -0.4637768 -0.8859509 0.001437306 -0.4637864 -0.8859472 0 -0.5397709 -0.8418118 -7.08654e-4 -0.5960216 -0.802968 -9.37221e-4 -0.8268204 0.5624489 -0.004387497 -0.6476134 -0.761969 -4.2097e-4 -0.6423141 -0.7664415 3.47175e-4 -0.6968266 -0.7172389 -0.001060187 -0.7304821 -0.6829317 -5.54295e-4 -0.7435929 -0.668632 9.92905e-4 -0.7859447 -0.618294 -0.001924037 0.6555852 0.7551212 2.10051e-4 0.8437642 0.5367141 -1.41321e-4 0.8273481 0.5616895 -4.20923e-4 0.8477767 0.5303536 1.27171e-4 0.824058 0.5665055 -1.63398e-4 0.7870002 0.6169528 -5.1292e-5 0.808875 0.5879807 1.40964e-4 0.7645833 0.6445248 -5.98896e-4 0.7569034 0.6535267 3.88747e-5 0.7310501 0.6823232 -9.33017e-4 0.7168827 0.6971937 4.28173e-4 0.7000097 0.7141334 1.96667e-4 0.6561374 0.7546415 1.50254e-4 0.6793889 0.7337782 -5.41629e-4 0.6387253 0.7694349 -3.69909e-4 0.607614 0.794232 -9.58491e-4 0.6109 0.7917077 -3.40499e-4 0.5505865 0.8347781 -8.39913e-5 0.5012162 0.8653221 1.4241e-4 0.4953029 0.8687204 -1.7756e-4 0.4527275 0.891649 2.571e-4 0.4396787 0.898155 -4.48309e-4 0.4019073 0.9156804 -3.05159e-4 0.2975571 0.954704 -3.53195e-4 0.3501585 0.9366905 1.3432e-4 0.3480658 0.9374701 1.83321e-5 0.2471922 0.9689665 -1.42339e-4 0.2853589 0.9584208 8.87976e-5 0.1910966 0.9815713 1.37788e-4 0.1857035 0.9826059 -1.89722e-4 0.137687 0.9904758 2.73549e-4 0.1237413 0.9923144 -5.95905e-4 0.0810759 0.996708 -1.53083e-4 0.0801177 0.9967855 -2.07401e-4 0.02227145 0.999752 -2.85617e-5 0.0194903 0.9998101 -2.20853e-4 -0.08734613 0.996178 -5.49478e-4 -0.03313881 0.9994506 7.57843e-4 -0.1222723 0.9924966 -2.34857e-4 -0.122783 0.9922747 -0.01776015 -0.2196931 0.975569 -4.27772e-4 -0.1722393 0.9850552 2.77673e-4 -0.2795521 0.9601303 -6.72401e-4 -0.3424634 0.939531 -7.08774e-4 -0.4037992 0.9148477 -2.56844e-4 -0.4047277 0.9144373 -3.44648e-4 -0.4571027 0.889414 0 -0.4543199 0.8908386 2.20297e-4 -0.4963686 0.8681119 -2.41394e-4 -0.5490638 0.8357804 -5.59976e-4 -0.5774854 0.816401 5.86574e-4 -0.6032503 0.7975515 -9.49472e-4 -0.6248398 0.7807525 9.93569e-4 -0.6547196 0.7558713 -0.001028001 -0.6717534 0.7407746 7.28336e-4 -0.7289284 0.6845896 -7.68835e-4 -0.6979185 0.716177 5.51203e-4 -0.7671435 0.6414743 -0.001271128 -0.8073711 0.5900435 -8.73127e-4 -0.8132868 0.5818631 4.30518e-4 -0.8445646 0.5354535 -5.09904e-4 -0.8476573 0.5305438 5.70136e-4 -0.8760021 0.4823069 -4.91952e-4 -0.8774657 0.4796394 0 -0.8980788 0.4398344 -5.98165e-4 -0.9235448 0.3834897 -8.22096e-4 -0.9572794 0.2891647 0 -0.9444895 0.3285419 0 -0.9582403 0.2859631 9.27451e-4 -0.9717415 0.2360458 -9.45427e-4 -0.9737089 0.2277882 0.001864612 -0.9830373 0.1833696 -0.003663241 -0.9866759 0.1626427 0.004242599 -0.9944444 0.1052607 7.39335e-4 -0.9971382 0.07558834 -0.001426994 -0.9996071 0.02798777 -0.001539766 -0.9996377 -0.02688801 -0.001234531 -0.9992366 -0.03905624 9.50247e-4 -0.9972149 -0.0745204 0.003071069 -0.9955455 -0.0942111 -0.003669679 -0.9906329 -0.1365486 -9.84127e-4 -0.9897989 -0.1424481 -0.002642869 -0.9769163 -0.2136163 0.00164318 -0.9817236 -0.1903055 0.00163716 -0.9731042 -0.2303441 -0.003134906 -0.9618071 -0.2737241 -0.00152719 -0.9580268 -0.2866789 0 -0.943282 -0.3319926 8.04569e-7 -0.945589 -0.3253638 2.83144e-7 -0.9334852 -0.3585968 -0.003715097 -0.9397992 -0.3417267 6.2665e-4 -0.9150294 -0.4033871 0 -0.9116346 -0.4109988 -0.001612067 -0.8910508 -0.4539023 -0.001159369 -0.8607252 -0.5090682 -0.001375615 -0.8334895 -0.5525353 1.82331e-4 -0.8252949 -0.5647017 6.31e-4 -0.818018 -0.5751922 -6.82455e-4 -0.8543016 -0.5197776 4.30323e-4 -0.8868339 -0.4620886 0 -0.915018 -0.4034132 1.05736e-5 -0.956461 -0.2915635 0.01316398 -0.9999918 0.003736317 0.001617014 -0.9982933 0.05839025 0.001069128 -0.9910311 0.1336034 -0.002753078 -0.9434626 0.3314786 7.10996e-4 -0.9212173 0.3890482 7.10259e-4 -0.8965603 0.4429219 0 -0.7846397 0.6199513 0.001027584 -0.7449243 0.6671481 0.001164138 -0.7038209 0.7103774 -5.07925e-4 -0.5404044 0.8414054 2.42735e-4 -0.4935222 0.8697333 0 -0.3638871 0.931443 4.93915e-4 -0.3057857 0.9521001 6.93168e-4 -0.241589 0.9703784 6.76842e-4 -0.1782558 0.9839842 -1.72797e-4 -0.1110252 0.9938176 2.56963e-4 -0.04789453 0.9988524 -4.02002e-4 0.2443645 0.9696835 -2.85894e-4 0.4059283 0.9139049 -1.39619e-4 0.554215 0.8323736 9.26639e-5 0.59499 0.8037324 0.001091361 0.7927411 0.6095584 -3.59325e-4 0.6541948 0.7563262 -1.03727e-5 -0.7762848 -0.6303824 4.30331e-4 -0.7318937 -0.6813261 -0.01124435 -0.6885126 -0.7252244 3.76145e-4 -0.589309 -0.8079078 3.11361e-5 -0.5319055 -0.8468037 3.33458e-4 -0.4196434 -0.9076891 -1.69224e-4 -0.3543694 -0.9351055 2.9793e-4 -0.2917367 -0.9564986 2.86907e-4 -0.2278336 -0.9737001 2.76661e-4 -0.1460618 -0.9892755 0 -0.09728795 -0.9952563 2.13323e-4 -0.03124797 -0.9995115 5.03249e-4 0.03495723 -0.9993888 2.68865e-4 0.1009765 -0.9948889 2.0312e-4 0.1665791 -0.9860281 1.93023e-4 0.2314394 -0.9728494 1.83811e-4 0.2952911 -0.9554073 1.75931e-4 0.4188262 -0.9080664 1.22579e-4 0.4733671 -0.8808652 -3.65814e-4 0.03574281 0.999361 0 0.03489005 0.9993912 3.69623e-4 0.5735784 -0.8191507 0 0.5735795 -0.8191499 0 0.9993909 -0.03489947 4.58515e-7 0.9993909 -0.03489971 -6.12581e-7 0.9993909 -0.03489965 0 0.9993909 -0.03489947 0 -0.03490024 -0.9993909 0 -0.03490102 -0.9993909 0 -0.9993909 0.03489911 0 -0.9993909 0.03489935 0 3.05069e-7 0 1 -4.19348e-6 0 1 1.42588e-6 0 1 -3.07651e-6 0 1 3.10282e-6 0 1 -6.50993e-6 0 1 -1.81774e-5 0 1 0 0 1 -1.79647e-6 0 1 1.4243e-6 0 1 4.79273e-6 0 1 5.83872e-6 0 1 0.9993906 -0.03490757 0 0.9993909 -0.03489953 4.24805e-5 -0.3420166 -0.9396939 0 -0.3420258 -0.9396907 0 -0.3420161 -0.9396941 5.28602e-6 -0.3420224 -0.9396918 0 2.04237e-6 -0.01745414 0.9998477 -6.70332e-6 -0.01744979 0.9998478 -4.07448e-6 -0.01745146 0.9998477 4.59162e-6 -0.01745384 0.9998477 -1.35601e-5 -0.01745742 0.9998477 1.00637e-6 -0.0174542 0.9998477 -1.0062e-5 -0.01745486 0.9998477 4.85526e-6 -0.01744943 0.9998478 1.23833e-5 -0.01743602 0.999848 0 -0.017452 0.9998477 8.75683e-6 -0.01745706 0.9998477 -3.75762e-6 -0.01745039 0.9998478 0 -0.01744025 0.999848 0 -0.0174517 0.9998477 -5.00157e-6 -0.01745223 0.9998478 -4.52107e-6 -0.01745182 0.9998477 4.18301e-6 -0.0174492 0.9998478 7.68782e-6 -0.01745229 0.9998478 -2.82759e-6 -0.01745086 0.9998478 0 -0.01744979 0.9998478 1.08449e-5 -0.01745539 0.9998477 -4.74635e-6 -0.02617597 0.9996574 1.07928e-6 -0.02617698 0.9996574 0 -0.02617716 0.9996574 1.4121e-5 -0.02617752 0.9996574 1.45967e-6 -0.02617615 0.9996573 0 -0.9996572 -0.02618187 0 -0.9996572 -0.02618438 0.7071077 -0.7068635 -0.0185157 0.7071059 -0.7068653 -0.01851391 0.5025086 0.8645572 0.005093574 0.5480134 0.8364697 0 0.5877825 0.8090191 0 0.6261881 0.779672 0 0.6631231 0.7485104 0 0.6985107 0.7155997 0 0.7322683 0.6810163 0 0.7643147 0.6448435 0 0.7945765 0.6071642 0 0.8229839 0.5680648 0 0.8494663 0.5276429 0 0.8739672 0.4859849 0 0.8964265 0.4431927 0 0.9167951 0.3993579 0 0.9350151 0.354608 0 0.9510558 0.3090194 0 0.9648749 0.2627101 0 0.9764406 0.2157867 0 0.9857267 0.1683539 0 0.9927088 0.1205372 0 0.997373 0.07243722 0 0.999708 0.02416461 0 0.999708 -0.02416461 0 0.997373 -0.07243722 0 0.9927088 -0.1205372 0 0.9857281 -0.1683457 0 0.97644 -0.2157894 0 0.9648771 -0.2627022 0 0.9510558 -0.3090194 0 0.9350142 -0.3546105 0 0.9167951 -0.3993579 0 0.8964253 -0.4431949 0 0.8739684 -0.4859828 0 0.8494663 -0.5276429 0 0.8229839 -0.5680648 0 0.7945792 -0.6071606 0 0.7643147 -0.6448435 0 0.7322697 -0.6810148 0 0.6985093 -0.715601 0 0.6631218 -0.7485116 0 0.6261881 -0.779672 0 0.5877811 -0.8090201 0 0.5480114 -0.8364709 0 0.5031356 -0.8642076 0 0.4566877 -0.8896272 0 0.4647112 -0.8854372 -0.006670355 0.4213988 -0.9068754 0 0.3770969 -0.9261739 0 0.3319097 -0.9433112 0 0.2859372 -0.9582338 -0.00528413 0.2911676 -0.9566712 0.001336216 0.2925502 -0.9562502 0 0.2437034 -0.9698395 0.004474461 0.1921221 -0.9813711 0 0.1444925 -0.989506 0 0.09651696 -0.9953314 0 0.0483123 -0.9988323 0 -0.0483123 -0.9988323 0 -0.09651702 -0.9953314 0 -0.1444926 -0.9895058 0 -0.1921222 -0.9813711 0 -0.2393178 -0.9709413 0 -0.2859412 -0.9582472 0 -0.3409166 -0.9400931 -0.001011848 -0.3300583 -0.9439606 0 -0.3319094 -0.9433096 -0.001783132 -0.3770965 -0.9261738 6.94154e-4 -0.4214009 -0.9068745 0 -0.4647213 -0.885457 0 -0.5069631 -0.8619678 0 -0.5480054 -0.836458 -0.00532031 -0.5423258 -0.8401628 -0.003082454 -0.5877825 -0.8090191 0 -0.6261881 -0.779672 0 -0.6631231 -0.7485104 0 -0.6985107 -0.7155997 0 -0.7322683 -0.6810163 0 -0.7655736 -0.6433485 0 -0.8076531 -0.5896571 -9.79594e-4 -0.7939509 -0.6079344 -0.007615327 -0.7981401 -0.6019635 -0.02475041 -0.7853548 -0.619042 -0.002233684 -0.8240379 -0.5663608 0.01403361 -0.8278435 -0.5608293 0.01207762 -0.8180334 -0.5751419 0.005784213 -0.8224688 -0.5686816 0.01209509 -0.8214346 -0.5686106 -0.04390233 -0.8438233 -0.5327934 0.06397962 -0.8739754 -0.4859701 0 -0.8964301 -0.4431852 0 -0.9167975 -0.3993526 0 -0.9350146 -0.3546095 0 -0.9510592 -0.3090088 0 -0.9648738 -0.2627139 0 -0.9764401 -0.2157885 0 -0.985727 -0.1683522 0 -0.9927089 -0.1205367 0 -0.9973731 -0.07243615 0 -0.9997081 -0.02416384 0 -0.999708 0.02416437 0 -0.9997074 0.02418857 0 -0.9997082 0.02416074 0 -0.9997081 0.02416616 0 -0.9972355 0.07430523 0 -0.9927071 0.1205313 -0.002210378 -0.9895349 0.1442183 -0.004683732 -0.985728 0.1683459 0 -0.9764402 0.2157882 0 -0.9648776 0.2627003 0 -0.9510554 0.3090206 0 -0.9350147 0.3546091 0 -0.9166343 0.3997269 0 -0.8964262 0.4431926 -6.42519e-4 -0.8863596 0.4629958 -0.00126034 -0.8739684 0.4859828 0 -0.8494663 0.5276429 0 -0.8229839 0.5680648 0 -0.7945792 0.6071606 0 -0.7643147 0.6448435 0 -0.7322697 0.6810148 0 -0.6985093 0.715601 0 -0.6631218 0.7485116 0 -0.6261881 0.779672 0 -0.5877811 0.8090201 0 -0.5423297 0.8401602 -0.003082454 -0.5547597 0.8320108 0 -0.5480043 0.8364587 -0.005321025 -0.5120986 0.8589209 0.003180205 -0.4647235 0.8854559 0 -0.4213988 0.9068754 0 -0.3759952 0.9266216 0 -0.3319097 0.9433095 -0.00178188 -0.3409076 0.9400963 -0.001011848 -0.285941 0.9582473 0 -0.2393177 0.9709414 0 -0.1921221 0.9813711 0 -0.1444925 0.989506 0 -0.09651696 0.9953314 0 -0.0483123 0.9988323 0 0.0483123 0.9988323 0 0.09651702 0.9953314 0 0.1444926 0.9895058 0 0.1946287 0.9808771 0 0.2441527 0.9697368 0 0.2393156 0.9709328 -0.004189908 0.2859409 0.9582473 0 0.3319101 0.9433111 0 0.3770964 0.926174 0 0.4213998 0.906875 0 0.4647133 0.8854424 -0.005768895 0.4592707 0.8882952 0.001429557 0.4577784 0.8890664 0 0.4214001 0.9068749 0 0.3770975 0.9261736 0 0.3319104 0.943311 0 0.2859408 0.9582474 0 0.2428025 0.9700748 0.001380741 0.1921221 0.9813668 0.002900063 0.1444932 0.9895059 0 0.09651732 0.9953313 0 0.04831248 0.9988323 0 -0.04831248 0.9988323 0 -0.09651738 0.9953313 0 -0.1444934 0.9895058 0 -0.1921229 0.981371 0 -0.2393165 0.9709416 0 -0.2859412 0.9582472 0 -0.3300583 0.9439606 0 -0.3770951 0.9261743 6.94251e-4 -0.4214009 0.9068745 0 -0.4647213 0.885457 0 -0.5069631 0.8619678 0 -0.5877843 0.8090177 0 -0.6631231 0.7485104 0 -0.6985107 0.7155997 0 -0.7322683 0.6810163 0 -0.7945785 0.6071615 0 -0.8229858 0.5680621 0 -0.8739686 0.4859825 0 -0.8961294 0.4437929 0 -0.9167932 0.399362 3.35768e-4 -0.9350141 0.3546106 0 -0.9510567 0.3090164 0 -0.9648749 0.2627101 0 -0.9857264 0.1683557 0 -0.9923269 0.123642 0 -0.9973723 0.07243484 0.001380801 -0.9997878 0.02033156 0.003333687 -0.999708 -0.02416503 0 -0.9927085 -0.1205398 0 -0.9857275 -0.1683492 0 -0.9764388 -0.2157945 0 -0.9648788 -0.2626954 0 -0.9510536 -0.3090263 0 -0.9350156 -0.3546068 0 -0.9167883 -0.3993735 0 -0.8964203 -0.443205 0 -0.8739637 -0.4859914 0 -0.8494625 -0.5276491 0 -0.7643104 -0.644845 0.002188503 -0.7322697 -0.6810148 0 -0.6985093 -0.715601 0 -0.6631218 -0.7485116 0 -0.5877829 -0.8090187 0 -0.5547597 -0.8320108 0 -0.5120996 -0.8589202 0.003180503 -0.4647235 -0.8854559 0 -0.4213986 -0.9068755 0 -0.3759947 -0.9266218 0 -0.285941 -0.9582473 0 -0.2393164 -0.9709417 0 -0.1921228 -0.981371 0 -0.1444932 -0.9895059 0 -0.09651732 -0.9953313 0 -0.04831248 -0.9988323 0 0.04831248 -0.9988323 0 0.09651738 -0.9953313 0 0.1444934 -0.9895058 0 0.1921229 -0.981371 0 0.2393165 -0.9709416 0 0.3319103 -0.943311 0 0.3770958 -0.9261744 0 0.4214009 -0.9068745 0 0.4592647 -0.8882959 0.002524435 0.5069552 -0.861955 0.005502343 0.5480154 -0.8364683 0 0.5877843 -0.8090177 0 0.6631231 -0.7485104 0 0.6985107 -0.7155997 0 0.7322683 -0.6810163 0 0.7945785 -0.6071615 0 0.8229858 -0.5680621 0 0.8739686 -0.4859825 0 0.8964275 -0.4431903 0 0.9167942 -0.39936 0 0.9350144 -0.3546099 0 0.9510564 -0.3090177 0 0.9648749 -0.2627101 0 0.9764406 -0.2157867 0 0.9857268 -0.168353 0 0.999708 -0.02416473 0 0.999708 0.02416473 0 0.9857282 0.1683447 0 0.97644 0.2157894 0 0.9648771 0.2627022 0 0.9510564 0.3090177 0 0.9350135 0.3546124 0 0.9167942 0.39936 0 0.8964264 0.4431927 0 0.8739697 0.4859803 0 0.8229858 0.5680621 0 0.7945812 0.6071579 0 0.7322697 0.6810148 0 0.6985093 0.715601 0 0.6631218 0.7485116 0 0.5877829 0.8090187 0 0.5480134 0.8364696 0 0.506964 0.8619673 0 -1.94303e-6 0 -1 1.31468e-7 0 -1 1.30212e-6 0 -1 6.02305e-7 0 -1 2.56938e-6 0 -1 4.71941e-7 0 -1 -4.05593e-7 0 -1 -2.5406e-6 0 -1 2.3978e-6 0 -1 -0.874614 -0.4848201 0 -0.8746253 -0.4847996 0 -0.9396934 -0.3420183 0 -0.9396931 -0.342019 0 -0.5735734 0.819154 -6.3419e-4 -0.5735886 0.8191435 0 0.6133483 -0.7854632 0.08277326 0.6038122 -0.7927932 0.08300626 0.5973714 -0.7975694 0.08384901 0.5906755 -0.8024359 0.08484798 0.5850018 -0.8065699 0.08495795 0.592647 -0.8010147 0.08452886 0.5640587 -0.8212612 0.08583682 0.5716646 -0.8159419 0.08624625 0.5353925 -0.8399674 0.08837217 0.5342541 -0.8406994 0.08830124 0.507454 -0.8569956 0.08971661 0.4993302 -0.8616452 0.0907582 0.4747233 -0.8753673 0.09148824 0.4417701 -0.8922161 0.09375303 0.4174073 -0.9037528 0.0948804 0.3962208 -0.9130111 0.09705591 0.6843957 -0.7246626 0.08041626 0.390816 -0.9154975 0.09553658 0.3914617 -0.9152206 0.09554618 0.3741418 -0.9222739 0.09710264 0.3401149 -0.9352865 0.09778124 0.296973 -0.9497196 0.09919679 0.2539903 -0.9619588 0.1006193 0.2130476 -0.9717038 0.1019927 0.1731661 -0.9795157 0.1027742 0.02989125 -0.9941388 0.103897 0.03988027 -0.9936718 0.1050047 0.07255733 -0.9918087 0.1051241 0.06138181 -0.9927101 0.1037256 0.09679681 -0.9898307 0.1042382 0.09121388 -0.9903563 0.1042814 0.1056325 -0.9888373 0.1050847 0.1033463 -0.9891068 0.1048209 0.1317124 -0.9858623 0.1035737 0.1231233 -0.9869654 0.1036341 0.1551826 -0.9825216 0.1028097 0.2785453 -0.955582 0.09631061 0.1558788 -0.9824204 0.1027238 0.1521883 -0.9829233 0.1034432 0.1425744 -0.9842829 0.1042104 0.1428309 -0.9842495 0.1041749 0.1481943 -0.9835066 0.1036974 0.1269494 -0.986471 0.1037243 0.07982069 -0.9913438 0.1042414 0.03116977 -0.993874 0.1060332 0.07544744 -0.9918823 0.102358 0.1226388 -0.9871236 0.1026985 0.1134691 -0.9880619 0.1042048 0.1668412 -0.980646 0.1024575 0.2127884 -0.9717628 0.1019725 0.2589232 -0.9606019 0.1010094 0.3035219 -0.9475911 0.09972792 0.3467411 -0.9327959 0.09829837 0.4313021 -0.897354 0.09345811 0.475098 -0.8751617 0.09151089 0.9106407 0.01422709 -0.4129542 0.866024 -1.16733e-5 -0.5000026 0.869372 -0.005392968 -0.4941291 0.8662769 0.005408525 -0.4995349 0.8660228 -2.14293e-5 -0.5000048 0.8660261 -2.12814e-6 -0.4999989 0.8660266 -1.50602e-6 -0.4999979 0.8662238 2.47706e-4 -0.4996562 0.9398363 6.94248e-4 -0.3416247 0.9283688 -0.001555502 -0.3716572 0.9991834 0.002464473 -0.04033017 0.9954695 -0.001539349 -0.09506964 0.9660828 -0.005066931 0.2581833 0.8572385 -0.003811299 0.5149055 0.6625707 -0.006040573 0.7489751 0.4447222 -0.004554808 0.895657 0.1961319 -0.003673851 0.9805707 -0.01097476 2.29635e-4 0.9999398 -0.3069452 0.002037644 0.9517251 -0.5957481 -0.002286195 0.8031681 -0.7687448 1.10765e-5 0.6395556 -0.7860652 -0.002394437 0.6181391 -0.5800545 -3.11776e-4 0.8145776 -0.3270297 -2.22306e-4 0.9450141 -0.04766935 -0.002593278 0.9988598 0.2357597 1.17056e-6 0.9718114 0.5000147 0.002110302 0.8660144 0.7237429 0.003116846 0.6900628 0.8888222 0.00324738 0.4582408 0.9819294 0.001894295 0.1892381 0.4326051 -0.9015836 5.1713e-5 0.4748287 -0.8800781 5.96187e-4 -0.00114727 -0.9999994 2.36374e-6 4.2853e-4 -1 -5.95887e-5 0.02307462 -0.9997335 8.40498e-4 0.02965712 -0.9995601 2.58592e-4 0.04361671 -0.9990484 4.21741e-5 0.07594323 -0.9971119 6.70285e-4 0.08446574 -0.9964265 2.52777e-4 0.1048761 -0.9944853 6.27137e-5 0.1258192 -0.9920532 3.77738e-4 0.1216111 -0.9925777 6.07255e-4 0.1432227 -0.9896906 9.49469e-5 0.1678127 -0.9858188 4.25602e-4 0.1640425 -0.9864531 6.81279e-4 0.1860091 -0.9825481 8.12239e-5 0.2130589 -0.9770392 4.7415e-4 0.213288 -0.9769893 4.6394e-4 0.007729232 -0.9999701 3.60975e-4 0.02767759 -0.9996168 -7.40141e-4 0.03893458 -0.9992417 2.27733e-4 0.06460809 -0.9979104 -7.16613e-4 0.06241124 -0.9980504 -4.65782e-4 0.08284157 -0.9965627 2.59187e-4 0.1037579 -0.9946024 -6.1815e-4 0.1047501 -0.9944985 -4.87601e-4 0.1241461 -0.992264 2.09853e-4 0.1420727 -0.989856 -7.56361e-4 0.1751894 -0.9845348 -3.98605e-4 0.1734428 -0.9848439 -2.96324e-4 0.1593238 -0.9872265 -9.07518e-5 0.1858532 -0.9825776 3.25076e-5 0.200691 -0.9796546 -1.83052e-4 0.211634 -0.9773489 -4.07111e-4 0.2219783 -0.9750516 -6.56403e-5 0.2389205 -0.9710391 9.99523e-5 0.2354864 -0.9718777 -2.98569e-4 0.2391236 -0.9709892 -1.57083e-4 0.2433742 -0.9699325 -2.65997e-5 0.2488609 -0.9685393 1.24185e-4 0.2390348 -0.9710111 8.94325e-5 0.2283902 -0.9735698 1.27286e-4 0.2345499 -0.9721041 8.67601e-5 0.2299821 -0.9731947 -6.11313e-4 0.2668184 -0.9637469 1.30348e-5 0.3003824 -0.9538189 2.49367e-5 0.3471182 -0.9378215 -5.73564e-5 0.3447692 -0.9386875 4.36876e-5 0.5864403 -0.8099925 -1.21891e-4 0.5812288 -0.8137403 -2.75205e-4 0.5915145 -0.8062944 1.29813e-5 0.5680037 -0.823026 -2.98194e-5 0.5545026 -0.8321821 1.08444e-4 0.5448813 -0.8385133 -3.53677e-4 0.5566298 -0.8307607 -7.33491e-5 0.5315414 -0.8470323 -1.12292e-4 0.5301138 -0.8479267 -1.64029e-4 0.5042824 -0.8635389 2.68306e-4 0.4958119 -0.8684299 -1.67082e-4 0.4657589 -0.8849118 1.04533e-4 0.4612596 -0.8872652 3.16444e-4 0.4284276 -0.9035762 -2.59302e-4 0.4314526 -0.9021357 -3.73442e-4 0.4271649 -0.9041737 -5.19541e-4 0.4190282 -0.9079733 -1.72978e-5 0.3985522 -0.9171457 1.56863e-5 0.4053087 -0.91418 6.59789e-5 0.3891317 -0.9211822 -1.71719e-4 0.3880181 -0.9216516 5.00077e-4 0.3881544 -0.9215943 4.75875e-4 0.3691118 -0.9293851 9.59946e-5 0.3443737 -0.9388327 4.37796e-5 0.3761276 -0.926568 1.31899e-4 0.3716672 -0.9283661 1.69732e-5 0.3733632 -0.9276853 9.66261e-6 0.3871824 -0.9220032 -2.36658e-4 0.3807649 -0.9246719 -8.49918e-5 0.5782753 -0.8158417 -4.44778e-4 0.6055799 -0.7957844 3.48912e-4 0.3036306 -0.9527899 1.3872e-4 0.2578992 -0.9661719 2.35661e-4 0.2092262 -0.9778671 -5.87805e-4 0.1445531 -0.989497 -4.94062e-4 0.2231479 -0.9747847 2.06996e-4 0.201921 -0.9794018 1.87505e-4 0.0638321 -0.9979607 1.14112e-4 0.5073459 -0.8617413 0.001425862 0.4753389 -0.8798019 0.001237034 0.4336121 -0.9010995 5.30304e-4 0 -1 4.7664e-6 0 -1 -1.43424e-6 0 -1 2.02988e-6 0 -1 -1.84238e-6 0 -1 -1.92017e-6 0 -1 -2.05612e-6 0 -1 1.03762e-6 -2.68402e-7 -1 7.65353e-7 -5.83528e-7 -1 1.51978e-6 -3.68328e-6 -1 7.03927e-7 -4.56538e-7 -1 0 -3.49466e-7 -1 1.38829e-6 -1.01514e-6 -1 -1.07529e-5 -2.55866e-7 -1 1.91788e-7 -1.65002e-7 -1 6.6173e-7 0 -1 0 -0.8660264 -3.02137e-6 0.4999983 -0.8659014 2.75172e-4 0.5002147 -0.863625 -0.003844976 0.5041201 -0.8090654 -0.004144787 0.5877042 -0.7432538 -3.57936e-4 0.6690095 -0.665978 -3.53657e-4 0.7459713 -0.5442326 -9.68595e-4 0.8389338 -0.3751809 0.006498575 0.9269289 -0.1544213 0.01069748 0.9879473 -0.1711917 0 0.9852378 -0.3899272 -0.003667891 0.9208385 -0.5463643 -0.002470314 0.837544 -0.658518 0.004158556 0.7525536 -0.74165 7.98237e-4 0.6707866 -0.8016964 7.91336e-4 0.5977309 -0.8475748 0.004018902 0.5306608 -1 0 -4.33822e-7 -1 0 -1.89607e-7 1.08206e-4 0 1 -9.93653e-7 0 1 1.76558e-6 0 1 5.29935e-6 0 1 -6.16625e-5 0 1 -2.0288e-5 0 1 -7.72902e-6 0 1 1.54149e-5 0 1 -1.8618e-5 0 1 2.0145e-6 0 1 5.93358e-6 0 1 -2.79936e-6 0 1 -1.48671e-6 0 1 -1.85649e-5 0 1 1.04242e-5 0 1 -5.58272e-6 0 1 -3.31587e-5 0 1 7.72902e-6 0 1 -4.98833e-5 0 1 1.32726e-5 0 1 9.04666e-6 0 1 -2.63302e-6 0 1 -1.54149e-5 0 1 -4.64924e-6 0 1 8.01667e-7 0 1 9.231e-5 0 1 5.5683e-7 0 1 3.29643e-7 0 1 1.6978e-5 0 1 4.34662e-6 0 1 1.28396e-5 0 1 5.29936e-6 0 1 -3.31409e-6 0 1 -5.93358e-6 0 1 -8.90928e-6 0 1 8.82803e-7 0 1 -1.00724e-6 0 1 -3.62218e-7 0 1 1.24705e-5 0 1 8.94747e-7 0 1 -5.1457e-6 0 1 4.64125e-6 0 1 5.1457e-6 0 1 -1.8565e-5 0 1 -4.64125e-6 0 1 -4.17789e-6 0 -1 -1.8744e-7 0 -1 -1.92709e-7 0 -1 -8.18176e-7 0 -1 2.05969e-6 0 -1 9.86921e-7 0 -1 1.87429e-6 0 -1 5.95397e-6 0 -1 2.18174e-6 0 -1 5.10761e-7 0 -1 4.72829e-6 0 -1 -3.99484e-7 0 -1 2.6787e-6 0 -1 -2.19746e-6 0 -1 -1.12726e-6 0 -1 -1.8811e-7 0 -1 5.46788e-7 0 -1 1.08365e-6 0 -1 -3.60497e-7 0 -1 1.83668e-6 0 -1 -7.98389e-7 0 -1 2.34922e-6 0 -1 6.02793e-7 0 -1 -5.22393e-7 0 -1 -7.14886e-7 0 -1 -2.90432e-6 0 -1 1.60819e-7 0 -1 3.972e-6 0 -1 -4.51076e-6 0 -1 2.03514e-7 0 -1 7.92685e-7 0 -1 1.81561e-7 0 -1 -1.80817e-7 0 -1 -1.45551e-6 0 -1 -2.95624e-6 0 -1 -4.61629e-6 0 -1 -5.86802e-6 0 -1 -4.06307e-6 0 -1 -6.37461e-7 0 -1 1.94836e-6 0 -1 -4.17856e-6 0 -1 7.72055e-6 0 -1 1.74776e-6 0 -1 8.35004e-6 0 -1 -1.44808e-6 0 -1 0 0 -1 5.96677e-7 0 -1 8.33421e-6 0 -1 3.27514e-6 0 -1 -3.81389e-7 0 -1 -3.77884e-7 0 -1 -3.77826e-6 0 -1 1.30786e-6 0 -1 1.33447e-6 0 -1 -7.83182e-7 0 -1 -1.84126e-7 0 -1 3.23651e-6 0 -1 -4.80417e-6 0 -1 1.16898e-6 0 -1 -2.31726e-6 0 -1 -6.03052e-5 0 -1 1.19306e-5 0 -1 7.86847e-6 0 -1 -1.15339e-5 0 -1 5.07213e-6 0 -1 0 0 -1 -4.89968e-6 0 -1 -1.43741e-5 0 -1 3.66234e-7 0 -1 -4.61087e-6 0 -1 5.56984e-6 0 -1 -9.29019e-6 0 -1 1.4182e-5 -1.38651e-5 -1 9.49823e-6 0 -1 -5.93506e-7 0 -1 4.17733e-4 0 -1 0.956305 -0.292371 0 4.55276e-6 0 -1 -3.02809e-6 0 -1 8.79783e-6 0 -1 -0.29237 -0.9563053 0 -0.292372 -0.9563047 0 -0.8829483 -0.4694705 0 -0.8829454 -0.4694758 0 -0.9563042 0.2923738 0 -0.9563048 0.2923719 0 -0.4694758 0.8829454 0 -0.4694759 0.8829453 0 0.292372 0.9563047 0 0.2923716 0.9563049 0 + + + + + + + + + + + + + + +

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

+
+
+
+ + + + 37.64515 77.31962 458.9959 77.64516 37.31962 458.9959 77.64516 77.31962 458.9959 77.64516 37.31962 644.4959 37.64515 77.31962 644.4959 -37.35485 77.31962 458.9959 -77.35485 77.31962 446.9959 -77.35485 77.31962 458.9959 77.64516 77.31962 446.9959 -37.35485 77.31962 644.4959 -77.35485 37.31962 458.9959 -77.35485 37.31962 644.4959 -77.35485 -77.68038 446.9959 77.64516 -77.68038 446.9959 -77.35485 -37.68038 644.4959 37.64515 -77.68038 644.4959 77.64516 -37.68038 644.4959 -37.35485 -77.68038 644.4959 -77.35485 -37.68038 458.9959 -77.35485 -77.68038 458.9959 -37.35485 -77.68038 458.9959 37.64515 -77.68038 458.9959 77.64516 -77.68038 458.9959 77.64516 -37.68038 458.9959 + + + + + + + + + + 0 0 1 0.7071067 0.7071069 0 0.7071067 0.7071068 0 0 1 0 -0.7071068 0.7071068 0 -0.7071067 0.7071068 0 0 0 -1 -2.60417e-6 0 1 2.60417e-6 0 1 -1 0 0 -0.7071068 -0.7071068 0 -0.7071067 -0.7071068 0 0 -1 0 1 0 0 0.7071067 -0.7071068 0 0.7071067 -0.7071069 0 + + + + + + + + + + + + + + +

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

+
+
+
+ + + + 297.6452 63.99584 597.6804 337.6452 63.99584 637.6804 337.6452 63.99584 597.6804 297.6452 249.4958 597.6804 337.6452 249.4958 637.6804 337.6452 51.99584 597.6804 222.6452 63.99584 597.6804 222.6452 249.4958 597.6804 182.6452 51.99584 597.6804 182.6452 63.99584 597.6804 182.6452 63.99584 637.6804 182.6452 249.4958 637.6804 337.6452 51.99584 752.6804 182.6452 51.99584 752.6804 297.6452 249.4958 752.6804 337.6452 249.4958 712.6804 182.6452 249.4958 712.6804 222.6452 249.4958 752.6804 182.6452 63.99584 712.6804 182.6452 63.99584 752.6804 222.6452 63.99584 752.6804 297.6452 63.99584 752.6804 337.6452 63.99584 752.6804 337.6452 63.99584 712.6804 + + + + + + + + + + 0 1 0 0.7071062 0 -0.7071075 0.7071068 0 -0.7071067 0 0 -1 -0.7071069 0 -0.7071067 -0.7071061 0 -0.7071075 0 -1 0 -1 0 0 -1 2.10013e-6 0 -0.7071053 0 0.7071083 -0.7071069 0 0.7071067 0 0 1 1 0 0 0.7071068 0 0.7071067 0.7071054 0 0.7071082 + + + + + + + + + + + + + + +

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

+
+
+
+
+ + + + + 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 + + + + 0.001 0 0 0 0 0.001 0 0 0 0 0.001 -0.675 0 0 0 1 + + + + + + + + + + 0.001 0 0 0 0 0.001 0 0 0 0 0.001 -0.675 0 0 0 1 + + + + + + + + + + 0.001 0 0 0 0 0.001 0 0 0 0 0.001 -0.675 0 0 0 1 + + + + + + + + + + + + + +
\ No newline at end of file diff --git a/kuka_kr16_support/meshes/kr16_2/visual/link_2.dae b/kuka_kr16_support/meshes/kr16_2/visual/link_2.dae new file mode 100644 index 000000000..49a255c36 --- /dev/null +++ b/kuka_kr16_support/meshes/kr16_2/visual/link_2.dae @@ -0,0 +1,100 @@ + + + + + Blender User + Blender 2.74.0 commit date:2015-03-31, commit time:13:39, hash:000dfc0 + + 2015-06-09T10:06:22 + 2015-06-09T10:06:22 + + Z_UP + + + + + + + + + 0 0 0 1 + + + 0 0 0 1 + + + 0.512 0.2088141 0.07027201 1 + + + 0.03125 0.03125 0.03125 1 + + + 1 + + + 1 + + + + + + + + + + + + + + + + 241.6021 -264.5 867.4687 246.2979 -264.5 868.9945 245 -264.5 869.2 248.9944 -264.5 863.7022 249.2 -264.5 865 243.7021 -264.5 861.0056 245 -264.5 860.8 241.6021 -264.5 862.5313 242.5313 -264.5 861.6021 241.0056 -264.5 866.2979 240.8 -264.5 865 241.0056 -264.5 863.7022 243.7021 -264.5 868.9945 248.3979 -264.5 867.4687 247.4687 -264.5 868.3979 248.9944 -264.5 866.2979 248.3979 -264.5 862.5313 246.2979 -264.5 861.0056 247.4687 -264.5 861.6021 242.5313 -264.5 868.3979 246.2979 -276.5 861.0056 247.4687 -276.5 861.6021 248.3979 -276.5 862.5313 248.9944 -276.5 863.7022 249.2 -276.5 865 248.9944 -276.5 866.2979 248.3979 -276.5 867.4687 247.4687 -276.5 868.3979 246.2979 -276.5 868.9945 245 -276.5 869.2 243.7021 -276.5 868.9945 242.5313 -276.5 868.3979 241.6021 -276.5 867.4687 241.0056 -276.5 866.2979 240.8 -276.5 865 241.0056 -276.5 863.7022 241.6021 -276.5 862.5313 242.5313 -276.5 861.6021 243.7021 -276.5 861.0056 245 -276.5 860.8 271.0056 -276.5 866.2979 231 -276.5 880.8369 271.0056 -276.5 863.7022 270.8 -276.5 865 273.7021 -276.5 861.0056 272.5313 -276.5 861.6021 271.6022 -276.5 867.4687 231 -276.5 847.8369 289 -276.5 847.8369 271.6022 -276.5 862.5313 275 -276.5 860.8 289 -276.5 880.8369 279.2 -276.5 865 273.7021 -276.5 868.9945 278.9945 -276.5 863.7022 278.3979 -276.5 862.5313 278.9945 -276.5 866.2979 275 -276.5 869.2 276.2979 -276.5 868.9945 272.5313 -276.5 868.3979 277.4687 -276.5 868.3979 278.3979 -276.5 867.4687 277.4687 -276.5 861.6021 276.2979 -276.5 861.0056 231 -275.5 880.8369 231 -275.5 847.8369 289 -275.5 880.8369 289 -275.5 847.8369 276.2979 -264.5 861.0056 275 -264.5 860.8 277.4687 -264.5 861.6021 278.3979 -264.5 862.5313 278.9945 -264.5 863.7022 279.2 -264.5 865 278.9945 -264.5 866.2979 278.3979 -264.5 867.4687 277.4687 -264.5 868.3979 276.2979 -264.5 868.9945 275 -264.5 869.2 273.7021 -264.5 868.9945 272.5313 -264.5 868.3979 271.6022 -264.5 867.4687 271.0056 -264.5 866.2979 270.8 -264.5 865 271.0056 -264.5 863.7022 271.6022 -264.5 862.5313 272.5313 -264.5 861.6021 273.7021 -264.5 861.0056 192.437 -269.632 847.8369 327.563 -269.632 847.8369 326.5845 -275.5 847.8369 193.4155 -275.5 847.8369 190.2614 -263.9998 815.8947 329.7386 -263.9998 815.8947 200.728 -275.5 1036.762 319.272 -275.5 1036.762 317.7155 -275.5 1109.292 202.2845 -275.5 1109.292 316.9367 -272.2915 1170.514 203.0634 -272.2915 1170.514 176.549 -130.5 1036.762 180.6042 -130.5 1225.728 202.6248 -262.5558 1225.728 343.451 -130.5 1036.762 339.3958 -130.5 1225.728 317.3752 -262.5558 1225.728 170.4076 -158.9232 755.6441 184.2726 -242.0703 755.6441 174.3007 -130.5 978.6748 169.4363 -212.7554 699.9946 183.8808 -241.4748 754.008 349.5924 -158.9232 755.6441 345.6994 -130.5 978.6748 335.7274 -242.0703 755.6441 336.1192 -241.4748 754.008 350.5637 -212.7554 699.9946 169.1434 -130.5 683.2182 169.1434 -144 683.2182 169.0554 -144 678.1759 169.0554 -201.1542 678.1759 350.8565 -144 683.2182 350.8565 -130.5 683.2182 350.9446 -201.1542 678.1759 350.9446 -144 678.1759 165.3561 -144 683.2182 165.0376 -144 677.6716 165.0438 -144 672.1158 169.0037 -144 674.1831 169.3837 -144 666.6519 165.3748 -144 666.5698 169.3913 -144 666.5698 165.0438 -140 672.1158 165.3748 -140 666.5698 165.0376 -140 677.6716 165.3561 -140 683.2182 150.8961 -140 676.0914 150.3562 -140 668.8901 152.0622 -140 683.2182 150.3164 -140 666.5698 152.0622 -128 683.2182 169.3719 -128 683.2182 169.3719 -130.5 683.2182 150.3164 -138 666.5698 169.3913 -138 666.5698 157.0231 -138 633.6829 160.1587 -138 627.1776 177.0364 -138 637.6096 180.417 -138 630.869 163.8496 -138 620.9705 168.0679 -138 615.1091 171.1363 -138 611.4393 185.1709 -138 623.2158 150.4463 -138 661.6691 154.4669 -138 640.4369 174.2255 -138 644.6069 172.0037 -138 651.8129 184.344 -138 624.4315 170.386 -138 659.1781 151.166 -138 654.4835 152.5096 -138 647.3881 184.344 -128 624.4315 188.7905 -128 618.3413 172.7813 -128 609.6379 180.417 -128 630.869 168.0679 -128 615.1091 157.0231 -128 633.6829 174.2255 -128 644.6069 177.0364 -128 637.6096 150.3562 -128 668.8901 150.8961 -128 676.0914 169.0037 -128 674.1831 163.8496 -128 620.9705 160.1587 -128 627.1776 154.4669 -128 640.4369 152.5096 -128 647.3881 172.0037 -128 651.8129 151.166 -128 654.4835 170.386 -128 659.1781 150.4463 -128 661.6691 169.3837 -128 666.6519 169.2485 -128 681.7199 177.954 -128 604.5986 193.726 -128 612.6401 183.5465 -128 600.0297 199.1166 -128 607.3671 200.4565 -128 606.1845 177.954 -140 604.5986 172.7813 -140 609.6379 171.1363 -140 611.4393 183.5465 -140 600.0297 186.385 -140 614.9514 182.0941 -140 620.634 191.0895 -140 609.6062 196.1812 -140 604.6284 200.4565 -144 606.1845 196.1812 -144 604.6284 185.1709 -144 623.2158 182.0941 -144 620.634 191.0895 -144 609.6062 186.385 -144 614.9514 188.7905 -144 618.3413 193.726 -144 612.6401 199.1166 -144 607.3671 350.9866 -144 676.5629 350.8036 -144 669.0243 354.9562 -144 672.115 354.6439 -144 683.2182 354.6251 -144 666.5687 354.9624 -144 677.6712 350.6086 -144 666.569 354.9624 -140 677.6712 354.6439 -140 683.2182 354.9562 -140 672.115 354.6251 -140 666.5687 369.1039 -140 676.0914 367.9378 -140 683.2182 369.6836 -140 666.5674 369.6438 -140 668.8901 367.9378 -128 683.2182 350.6282 -128 683.2182 350.6282 -130.5 683.2182 350.6086 -138 666.569 369.6836 -138 666.5674 359.8414 -138 627.1776 343.9129 -138 639.7918 340.7098 -138 632.9652 368.834 -138 654.4835 369.5537 -138 661.6691 349.9971 -138 661.5268 351.9321 -138 615.1091 336.9525 -138 626.4272 334.8305 -138 623.2178 356.1504 -138 620.9705 346.5399 -138 646.8602 362.9769 -138 633.6829 348.5726 -138 654.1218 367.4904 -138 647.3881 365.5331 -138 640.4369 348.8653 -138 611.4411 359.8414 -128 627.1776 356.1504 -128 620.9705 340.7098 -128 632.9652 346.5399 -128 646.8602 365.5331 -128 640.4369 362.9769 -128 633.6829 343.9129 -128 639.7918 368.834 -128 654.4835 348.5726 -128 654.1218 349.9971 -128 661.5268 351.9321 -128 615.1091 336.9525 -128 626.4272 327.882 -128 614.3944 342.046 -128 604.5986 336.4535 -128 600.0297 369.5537 -128 661.6691 350.8036 -128 669.0243 347.2187 -128 609.6379 332.6667 -128 620.2227 319.5435 -128 606.1845 322.6311 -128 608.9822 367.4904 -128 647.3881 350.9866 -128 676.5629 369.1039 -128 676.0914 369.6438 -128 668.8901 342.046 -140 604.5986 336.4535 -140 600.0297 347.2187 -140 609.6379 348.8653 -140 611.4411 333.616 -140 614.9526 328.911 -140 609.6068 337.9073 -140 620.636 323.8188 -140 604.6284 319.5435 -144 606.1845 323.8188 -144 604.6284 334.8305 -144 623.2178 337.9073 -144 620.636 333.616 -144 614.9526 328.911 -144 609.6068 332.6667 -144 620.2227 327.882 -144 614.3944 322.6311 -144 608.9822 192.7841 -247.3317 1276.977 180.4397 -218.9356 1330.382 178.8303 -130.5 1238.178 202.0346 -261.9503 1229.162 327.2159 -247.3317 1276.977 341.1697 -130.5 1238.178 339.5603 -218.9356 1330.382 317.9655 -261.9503 1229.162 180.6869 -134.5 1344.539 180.7578 -209.2474 1348.603 180.7578 -134.5 1348.603 180.6869 -130.5 1344.539 339.3132 -134.5 1344.539 339.2422 -134.5 1348.603 339.2422 -209.2474 1348.603 339.3132 -130.5 1344.539 337.6427 -134.5 1374.277 336.4804 -134.5 1376.702 338.1106 -134.5 1369.798 335.6351 -134.5 1381.064 334.2413 -134.5 1383.434 329.8645 -134.5 1393.974 328.0122 -134.5 1396.165 331.4111 -134.5 1389.939 326.1466 -134.5 1399.996 324.0718 -134.5 1402.064 321.911 -134.5 1405.666 319.6212 -134.5 1407.589 317.1908 -134.5 1410.939 314.6959 -134.5 1412.694 339.5111 -134.5 1346.168 333.0356 -134.5 1387.647 312.0231 -134.5 1415.775 309.3351 -134.5 1417.34 306.4483 -134.5 1420.135 303.5815 -134.5 1421.49 300.5098 -134.5 1423.985 297.4808 -134.5 1425.11 294.2544 -134.5 1427.296 291.0817 -134.5 1428.172 339.9804 -134.5 1353.23 339.497 -134.5 1355.692 339.8239 -134.5 1360.306 339.1188 -134.5 1362.776 274.0855 -134.5 1433.75 270.6127 -134.5 1433.788 277.594 -134.5 1432.529 267.0704 -134.5 1434.687 263.547 -134.5 1434.421 260 -134.5 1435 256.453 -134.5 1434.421 225.7456 -134.5 1427.296 219.4902 -134.5 1423.985 222.5192 -134.5 1425.11 213.5518 -134.5 1420.135 216.4186 -134.5 1421.49 207.9769 -134.5 1415.775 210.6649 -134.5 1417.34 202.8092 -134.5 1410.939 205.3041 -134.5 1412.694 339.0426 -134.5 1367.34 252.9296 -134.5 1434.687 245.9145 -134.5 1433.75 249.3873 -134.5 1433.788 239.0097 -134.5 1432.197 242.406 -134.5 1432.529 232.2691 -134.5 1430.04 235.5649 -134.5 1430.652 228.9183 -134.5 1428.172 190.1356 -134.5 1393.974 186.9644 -134.5 1387.647 188.589 -134.5 1389.939 184.3649 -134.5 1381.064 185.7587 -134.5 1383.434 180.9574 -134.5 1367.34 180.1761 -134.5 1360.306 180.8812 -134.5 1362.776 180.0196 -134.5 1353.23 180.503 -134.5 1355.692 180.489 -134.5 1346.168 287.7309 -134.5 1430.04 284.4351 -134.5 1430.652 280.9903 -134.5 1432.197 198.089 -134.5 1405.666 200.3788 -134.5 1407.589 193.8535 -134.5 1399.996 195.9282 -134.5 1402.064 191.9878 -134.5 1396.165 182.3573 -134.5 1374.277 183.5196 -134.5 1376.702 181.8894 -134.5 1369.798 252.9296 -117 1434.687 245.9145 -117 1433.75 239.0097 -117 1432.197 232.2691 -117 1430.04 225.7456 -117 1427.296 219.4902 -117 1423.985 213.5518 -117 1420.135 207.9769 -117 1415.775 202.8092 -117 1410.939 198.089 -117 1405.666 193.8535 -117 1399.996 190.1356 -117 1393.974 186.9644 -117 1387.647 184.3649 -117 1381.064 182.3573 -117 1374.277 180.9574 -117 1367.34 180.1761 -117 1360.306 180.0196 -117 1353.23 180.489 -117 1346.168 339.9804 -117 1353.23 339.8239 -117 1360.306 339.0426 -117 1367.34 337.6427 -117 1374.277 335.6351 -117 1381.064 333.0356 -117 1387.647 329.8645 -117 1393.974 326.1466 -117 1399.996 321.911 -117 1405.666 317.1908 -117 1410.939 312.0231 -117 1415.775 306.4483 -117 1420.135 300.5098 -117 1423.985 294.2544 -117 1427.296 287.7309 -117 1430.04 280.9903 -117 1432.197 274.0855 -117 1433.75 267.0704 -117 1434.687 260 -117 1435 338.4194 -117 1339.176 338.4194 -130.5 1339.176 336.714 -130.5 1332.307 336.714 -117 1332.307 334.4082 -130.5 1325.616 334.4082 -117 1325.616 331.52 -130.5 1319.155 331.52 -117 1319.155 328.0721 -130.5 1312.974 328.0721 -117 1312.974 324.0915 -130.5 1307.122 324.0915 -117 1307.122 319.6092 -130.5 1301.645 319.6092 -117 1301.645 314.6605 -130.5 1296.586 314.6605 -117 1296.586 309.2839 -130.5 1291.983 309.2839 -117 1291.983 303.5216 -130.5 1287.874 303.5216 -117 1287.874 297.4187 -130.5 1284.291 297.4187 -117 1284.291 291.023 -130.5 1281.26 291.023 -117 1281.26 284.3845 -130.5 1278.807 284.3845 -117 1278.807 277.5551 -130.5 1276.95 277.5551 -117 1276.95 270.5883 -130.5 1275.704 270.5883 -117 1275.704 263.5387 -130.5 1275.078 256.4613 -130.5 1275.078 260 -117 1275 256.4613 -117 1275.078 249.4117 -130.5 1275.704 249.4117 -117 1275.704 242.4449 -130.5 1276.95 242.4449 -117 1276.95 235.6155 -130.5 1278.807 235.6155 -117 1278.807 228.977 -130.5 1281.26 228.977 -117 1281.26 222.5812 -130.5 1284.291 222.5812 -117 1284.291 216.4784 -130.5 1287.874 216.4784 -117 1287.874 210.7161 -130.5 1291.983 210.7161 -117 1291.983 205.3395 -130.5 1296.586 205.3395 -117 1296.586 200.3908 -130.5 1301.645 200.3908 -117 1301.645 195.9085 -130.5 1307.122 195.9085 -117 1307.122 191.9279 -130.5 1312.974 191.9279 -117 1312.974 188.48 -130.5 1319.155 188.48 -117 1319.155 185.5918 -130.5 1325.616 185.5918 -117 1325.616 183.286 -130.5 1332.307 183.286 -117 1332.307 181.5806 -130.5 1339.176 181.5806 -117 1339.176 339.5111 -117 1346.168 263.5387 -117 1275.078 280.515 -83 763.6574 280.515 -130.5 763.6574 287.7849 -130.5 761.6545 287.7849 -83 761.6545 294.864 -130.5 759.0566 294.864 -83 759.0566 301.7037 -130.5 755.8814 301.7037 -83 755.8814 308.257 -130.5 752.1509 308.257 -83 752.1509 314.479 -130.5 747.8906 314.479 -83 747.8906 320.3269 -130.5 743.1298 320.3269 -83 743.1298 325.7605 -130.5 737.9012 325.7605 -83 737.9012 330.7426 -130.5 732.2406 330.7426 -83 732.2406 335.2389 -130.5 726.187 335.2389 -83 726.187 339.2186 -130.5 719.7819 339.2186 -83 719.7819 342.6543 -130.5 713.0693 342.6543 -83 713.0693 345.5224 -130.5 706.0953 345.5224 -83 706.0953 347.8033 -130.5 698.9078 347.8033 -83 698.9078 349.4813 -130.5 691.556 349.4813 -83 691.556 350.5448 -130.5 684.0906 350.9866 -83 676.5629 350.5448 -83 684.0906 350.8036 -83 669.0243 349.9971 -83 661.5268 348.5726 -83 654.1218 346.5399 -83 646.8602 343.9129 -83 639.7918 340.7098 -83 632.9652 336.9525 -83 626.4272 332.6667 -83 620.2227 327.882 -83 614.3944 350.9866 -200.2965 676.5629 350.9732 -198.2914 672.7917 350.8036 -196.2882 669.0243 350.478 -194.2905 665.2672 349.9971 -192.3017 661.5268 349.3616 -190.3252 657.8096 348.5726 -188.3644 654.1218 347.6315 -186.4227 650.4699 346.5399 -184.5033 646.8602 345.2997 -182.6097 643.2988 343.9129 -180.745 639.7918 342.3821 -178.9125 636.3453 340.7098 -177.1152 632.9652 338.8989 -175.3564 629.6572 336.9525 -173.6389 626.4272 334.8739 -171.9658 623.2805 332.6667 -170.3399 620.2227 330.0653 -168.5904 616.9323 327.882 -167.7658 614.3944 325.3126 -166.8688 611.6339 322.6311 -166.0073 608.9822 319.842 -165.1825 606.4439 316.9501 -164.3961 604.0234 316.9501 -83 604.0234 322.6311 -83 608.9822 313.9605 -163.6492 601.7247 310.8782 -162.9432 599.552 310.8782 -83 599.552 307.7084 -162.2793 597.5087 304.4568 -161.6587 595.5985 304.4568 -83 595.5985 301.1288 -161.0823 593.8248 297.7302 -160.5513 592.1904 297.7302 -83 592.1904 294.2668 -160.0664 590.6983 290.7445 -159.6287 589.3508 290.7445 -83 589.3508 287.1694 -159.2387 588.1506 283.5476 -158.8971 587.0994 283.5476 -83 587.0994 279.8855 -158.6046 586.1993 276.1891 -158.3617 585.4516 276.1891 -83 585.4516 272.465 -158.1688 584.8577 268.7195 -158.0261 584.4187 261.1899 -83 584.0078 268.7195 -83 584.4187 264.9589 -157.934 584.1352 261.1899 -157.8926 584.0078 257.4188 -157.902 584.0366 253.6522 -83 584.2217 246.158 -83 585.0589 253.6522 -157.9621 584.2217 249.8964 -158.0729 584.5626 238.7589 -83 586.5137 246.158 -158.2341 585.0589 242.4434 -158.4456 585.7097 231.5057 -83 588.5762 238.7589 -158.7068 586.5137 235.1109 -159.0175 587.4698 224.4481 -83 591.2321 231.5057 -159.3769 588.5762 227.9494 -159.7847 589.831 217.6347 -83 594.4632 224.4481 -160.2399 591.2321 221.0079 -160.7419 592.777 211.1121 -83 598.2473 217.6347 -161.2897 594.4632 214.3342 -161.8825 596.2877 204.9253 -83 602.5585 211.1121 -162.5193 598.2473 207.974 -163.1988 600.3388 169.0037 -199.0312 674.1831 169.3837 -195.0268 666.6519 169.1156 -197.0269 670.4136 170.386 -191.0529 659.1781 169.8074 -193.0343 662.9046 172.0037 -187.1367 651.8129 171.1185 -189.0859 655.4787 174.2255 -183.3052 644.6069 173.0399 -185.2087 648.1868 177.0364 -179.5847 637.6096 175.5585 -181.4295 641.0791 180.417 -176.0007 630.869 178.6568 -177.7741 634.2043 184.344 -172.5778 624.4315 182.3138 -174.2676 627.6096 188.7905 -169.3396 618.3413 186.5042 -170.9342 621.3403 193.726 -167.1958 612.6401 189.9347 -168.5904 616.9323 199.1166 -165.4825 607.3671 196.3667 -166.321 609.9477 199.1166 -83 607.3671 204.9253 -163.9201 602.5585 201.9711 -164.6817 604.9025 193.726 -83 612.6401 188.7905 -83 618.3413 184.344 -83 624.4315 180.417 -83 630.869 177.0364 -83 637.6096 174.2255 -83 644.6069 172.0037 -83 651.8129 170.386 -83 659.1781 169.3837 -83 666.6519 169.0037 -83 674.1831 170.1164 -130.5 689.2105 170.1164 -83 689.2105 169.2485 -83 681.7199 171.6016 -130.5 696.6036 171.6016 -83 696.6036 173.6937 -130.5 703.8483 173.6937 -83 703.8483 176.3785 -130.5 710.895 176.3785 -83 710.895 179.6375 -130.5 717.6951 179.6375 -83 717.6951 183.4483 -130.5 724.202 183.4483 -83 724.202 187.7848 -130.5 730.3712 187.7848 -83 730.3712 192.6172 -130.5 736.1601 192.6172 -83 736.1601 197.9122 -130.5 741.529 197.9122 -83 741.529 203.6336 -130.5 746.4411 203.6336 -83 746.4411 209.7421 -130.5 750.8626 209.7421 -83 750.8626 216.1956 -130.5 754.7633 216.1956 -83 754.7633 222.9499 -130.5 758.1162 222.9499 -83 758.1162 229.9587 -130.5 760.8983 229.9587 -83 760.8983 237.1737 -130.5 763.0906 237.1737 -83 763.0906 244.5455 -130.5 764.6781 244.5455 -83 764.6781 252.0234 -130.5 765.6497 252.0234 -83 765.6497 314.5317 -168.5904 616.9323 206.8891 -168.1062 615.4421 205.4684 -168.5904 616.9323 313.1109 -168.1062 615.4421 308.3088 -166.6491 610.9575 211.6912 -166.6491 610.9575 303.1296 -165.3354 606.9143 216.8704 -165.3354 606.9143 297.6137 -164.1753 603.3439 222.3863 -164.1753 603.3439 291.8042 -163.1779 600.2744 228.1958 -163.1779 600.2744 285.7465 -162.3511 597.7296 234.2535 -162.3511 597.7296 279.4878 -161.7012 595.7294 240.5122 -161.7012 595.7294 273.077 -161.2333 594.2895 246.923 -161.2333 594.2895 266.5641 -160.9511 593.421 253.4359 -160.9511 593.421 260 -160.8568 593.1307 246.375 -83 801.3121 292.0272 -83 801.3121 246.375 -90.5 801.3121 292.0272 -90.5 801.3121 245.3514 -130.5 807.775 245.3514 -90.5 807.775 292.7216 -130.5 803.5834 292.7216 -90.5 803.5834 252.7065 -130.5 842.3778 252.7065 -90.5 842.3778 256.3302 -130.5 845.3121 256.3302 -90.5 845.3121 265.2762 -130.5 845.3121 265.2762 -90.5 845.3121 271.4548 -90.5 841.9575 291.7125 -90.5 810.7633 271.4548 -130.5 841.9575 291.7125 -130.5 810.7633 330 -184.6536 647.1428 317.4984 -170.3986 620.3331 330 -208.272 691.5626 320.9063 -241.4748 754.008 330 -142.5 691.5626 330 -142.5 647.1428 317.4984 -142.5 620.3331 202.5016 -142.5 620.3331 202.5016 -170.3986 620.3331 206.8891 -142.5 615.4421 211.6912 -142.5 610.9575 216.8704 -142.5 606.9143 222.3863 -142.5 603.3439 228.1958 -142.5 600.2744 234.2535 -142.5 597.7296 240.5122 -142.5 595.7294 246.923 -142.5 594.2895 253.4359 -142.5 593.421 266.5641 -142.5 593.421 260 -142.5 593.1307 273.077 -142.5 594.2895 279.4878 -142.5 595.7294 285.7465 -142.5 597.7296 291.8042 -142.5 600.2744 297.6137 -142.5 603.3439 303.1296 -142.5 606.9143 308.3088 -142.5 610.9575 313.1109 -142.5 615.4421 319.4308 -142.5 764.1403 319.4308 -245.1627 764.1403 313.3137 -142.5 778.9082 313.3137 -250.5378 778.9082 294.1422 -142.5 798.0798 294.1422 -257.5157 798.0798 274.4853 -142.5 806.2219 274.4853 -260.4792 806.2219 245.5147 -260.4792 806.2219 245.5147 -142.5 806.2219 225.8579 -257.5157 798.0798 225.8579 -142.5 798.0798 206.6863 -250.5378 778.9082 206.6863 -142.5 778.9082 200.5692 -245.1627 764.1403 199.0937 -241.4748 754.008 200.5692 -142.5 764.1403 190 -184.6536 647.1428 190 -208.272 691.5626 190 -142.5 691.5626 190 -142.5 647.1428 253.3812 -142.5 751.6908 260 -142.5 752 240.3736 -142.5 749.2335 246.82 -142.5 750.7659 222.2766 -142.5 741.1494 207.1195 -142.5 728.3778 211.7665 -142.5 733.1011 285.9019 -142.5 747.1067 234.0981 -142.5 747.1067 216.8336 -142.5 737.3707 193.4799 -142.5 705.8209 196.0835 -142.5 711.914 312.8805 -142.5 728.3778 317.0669 -142.5 723.2418 303.1664 -142.5 737.3707 308.2335 -142.5 733.1011 279.6264 -142.5 749.2335 273.18 -142.5 750.7659 266.6188 -142.5 751.6908 228.0482 -142.5 744.4041 202.9331 -142.5 723.2418 199.2437 -142.5 717.7379 303.1664 -142.5 612.6293 297.7234 -142.5 741.1494 291.9518 -142.5 605.5959 285.9019 -142.5 602.8933 297.7234 -142.5 608.8507 308.2335 -142.5 616.8989 320.7563 -142.5 717.7379 291.9518 -142.5 744.4041 199.2437 -142.5 632.2622 196.0835 -142.5 638.086 211.7665 -142.5 616.8989 207.1195 -142.5 621.6222 312.8805 -142.5 621.6222 216.8336 -142.5 612.6293 222.2766 -142.5 608.8507 228.0482 -142.5 605.5959 234.0981 -142.5 602.8933 240.3736 -142.5 600.7666 246.82 -142.5 599.2341 279.6264 -142.5 600.7666 273.18 -142.5 599.2341 317.0669 -142.5 626.7582 323.9165 -142.5 638.086 326.5201 -142.5 644.1791 202.9331 -142.5 626.7582 253.3812 -142.5 598.3092 326.5201 -142.5 705.8209 323.9165 -142.5 711.914 193.4799 -142.5 644.1791 260 -142.5 598 266.6188 -142.5 598.3092 320.7563 -142.5 632.2622 323.9165 -142.2 711.914 326.5201 -142.2 705.8209 320.7563 -142.2 717.7379 317.0669 -142.2 723.2418 312.8805 -142.2 728.3778 308.2335 -142.2 733.1011 303.1664 -142.2 737.3707 297.7234 -142.2 741.1494 291.9518 -142.2 744.4041 285.9019 -142.2 747.1067 279.6264 -142.2 749.2335 273.18 -142.2 750.7659 266.6188 -142.2 751.6908 260 -142.2 752 253.3812 -142.2 751.6908 246.82 -142.2 750.7659 240.3736 -142.2 749.2335 234.0981 -142.2 747.1067 228.0482 -142.2 744.4041 222.2766 -142.2 741.1494 216.8336 -142.2 737.3707 211.7665 -142.2 733.1011 207.1195 -142.2 728.3778 202.9331 -142.2 723.2418 199.2437 -142.2 717.7379 196.0835 -142.2 711.914 193.4799 -142.2 705.8209 193.4799 -142.2 644.1791 196.0835 -142.2 638.086 199.2437 -142.2 632.2622 202.9331 -142.2 626.7582 207.1195 -142.2 621.6222 211.7665 -142.2 616.8989 216.8336 -142.2 612.6293 222.2766 -142.2 608.8507 228.0482 -142.2 605.5959 234.0981 -142.2 602.8933 240.3736 -142.2 600.7666 246.82 -142.2 599.2341 253.3812 -142.2 598.3092 260 -142.2 598 266.6188 -142.2 598.3092 273.18 -142.2 599.2341 279.6264 -142.2 600.7666 285.9019 -142.2 602.8933 291.9518 -142.2 605.5959 297.7234 -142.2 608.8507 303.1664 -142.2 612.6293 308.2335 -142.2 616.8989 312.8805 -142.2 621.6222 317.0669 -142.2 626.7582 320.7563 -142.2 632.2622 323.9165 -142.2 638.086 326.5201 -142.2 644.1791 289 -264.9479 1212.162 231 -270.5 1180.674 231 -264.9479 1212.162 289 -270.5 1180.674 231 -270.5 1212.162 289 -270.5 1212.162 271.0056 -270.5 1193.702 270.8 -270.5 1195 249.2 -270.5 1195 271.0056 -270.5 1196.298 248.9944 -270.5 1196.298 278.9945 -270.5 1196.298 279.2 -270.5 1195 248.9944 -270.5 1193.702 248.3979 -270.5 1197.469 278.9945 -270.5 1193.702 272.5313 -270.5 1198.398 273.7021 -270.5 1198.994 248.3979 -270.5 1192.531 278.3979 -270.5 1192.531 277.4687 -270.5 1191.602 278.3979 -270.5 1197.469 271.6022 -270.5 1197.469 271.6022 -270.5 1192.531 276.2979 -270.5 1198.994 277.4687 -270.5 1198.398 273.7021 -270.5 1191.006 272.5313 -270.5 1191.602 240.8 -270.5 1195 247.4687 -270.5 1191.602 241.0056 -270.5 1196.298 241.6021 -270.5 1192.531 241.0056 -270.5 1193.702 276.2979 -270.5 1191.006 275 -270.5 1199.2 246.2979 -270.5 1198.994 247.4687 -270.5 1198.398 241.6021 -270.5 1197.469 242.5313 -270.5 1198.398 245 -270.5 1199.2 243.7021 -270.5 1191.006 242.5313 -270.5 1191.602 246.2979 -270.5 1191.006 275 -270.5 1190.8 243.7021 -270.5 1198.994 245 -270.5 1190.8 246.2979 -258.5 1191.006 245 -258.5 1190.8 247.4687 -258.5 1191.602 248.3979 -258.5 1192.531 248.9944 -258.5 1193.702 249.2 -258.5 1195 248.9944 -258.5 1196.298 248.3979 -258.5 1197.469 247.4687 -258.5 1198.398 246.2979 -258.5 1198.994 245 -258.5 1199.2 243.7021 -258.5 1198.994 242.5313 -258.5 1198.398 241.6021 -258.5 1197.469 241.0056 -258.5 1196.298 240.8 -258.5 1195 241.0056 -258.5 1193.702 241.6021 -258.5 1192.531 242.5313 -258.5 1191.602 243.7021 -258.5 1191.006 276.2979 -258.5 1191.006 275 -258.5 1190.8 277.4687 -258.5 1191.602 278.3979 -258.5 1192.531 278.9945 -258.5 1193.702 279.2 -258.5 1195 278.9945 -258.5 1196.298 278.3979 -258.5 1197.469 277.4687 -258.5 1198.398 276.2979 -258.5 1198.994 275 -258.5 1199.2 273.7021 -258.5 1198.994 272.5313 -258.5 1198.398 271.6022 -258.5 1197.469 271.0056 -258.5 1196.298 270.8 -258.5 1195 271.0056 -258.5 1193.702 271.6022 -258.5 1192.531 272.5313 -258.5 1191.602 273.7021 -258.5 1191.006 232.8113 -250.7179 1265.901 221.7354 -247.3317 1276.977 250.1664 -252.9158 1258.712 269.8336 -252.9158 1258.712 298.2646 -247.3317 1276.977 287.1887 -250.7179 1265.901 269.8336 -152.5 1258.712 287.1887 -152.5 1265.901 250.1664 -152.5 1258.712 232.8113 -152.5 1265.901 299.7782 -246.5269 1278.49 299.7782 -152.5 1278.49 220.2218 -152.5 1278.49 220.2218 -246.5269 1278.49 308.1007 -235.8437 1298.583 308.1007 -152.5 1298.583 322.996 -198.5832 1368.66 322.996 -152.5 1368.66 315.0645 -186.3354 1391.694 315.0645 -152.5 1391.694 211.8993 -152.5 1298.583 211.8993 -235.8437 1298.583 326.1078 -182.3664 1399.159 324.0718 -180.8215 1402.064 313.1952 -184.9205 1394.355 193.8922 -182.3664 1399.159 204.9355 -186.3354 1391.694 206.8048 -184.9205 1394.355 328.0122 -183.958 1396.165 321.9082 -179.3264 1404.876 311.1975 -183.5562 1396.921 195.9282 -180.8215 1402.064 208.8025 -183.5562 1396.921 319.6212 -177.8842 1407.589 309.0761 -182.2457 1399.386 198.0919 -179.3264 1404.876 210.9239 -182.2457 1399.386 191.9878 -183.958 1396.165 317.2155 -176.4977 1410.196 306.8361 -180.9922 1401.743 200.3788 -177.8842 1407.589 213.1639 -180.9922 1401.743 314.6959 -175.1696 1412.694 304.4831 -179.7987 1403.988 202.7845 -176.4977 1410.196 215.5169 -179.7987 1403.988 312.0673 -173.9026 1415.077 302.0226 -178.6682 1406.114 207.9327 -173.9026 1415.077 205.3041 -175.1696 1412.694 309.3351 -172.6992 1417.34 299.4607 -177.6032 1408.117 210.6649 -172.6992 1417.34 217.9774 -178.6682 1406.114 306.5046 -171.5618 1419.479 296.8034 -176.6065 1409.992 213.4954 -171.5618 1419.479 220.5393 -177.6032 1408.117 303.5815 -170.4927 1421.49 294.0572 -175.6804 1411.733 300.5715 -169.4941 1423.368 291.2288 -174.8272 1413.338 219.4285 -169.4941 1423.368 216.4186 -170.4927 1421.49 225.9428 -175.6804 1411.733 223.1966 -176.6065 1409.992 228.7712 -174.8272 1413.338 222.5192 -168.5678 1425.11 297.4808 -168.5678 1425.11 294.3154 -167.7158 1426.713 288.325 -174.0489 1414.802 231.675 -174.0489 1414.802 291.0817 -166.9397 1428.172 285.3528 -173.3473 1416.121 225.6846 -167.7158 1426.713 234.6473 -173.3473 1416.121 287.7861 -166.2411 1429.486 282.3193 -172.7243 1417.293 228.9183 -166.9397 1428.172 237.6807 -172.7243 1417.293 284.4351 -165.6213 1430.652 279.2319 -172.1813 1418.314 235.5649 -165.6213 1430.652 232.2139 -166.2411 1429.486 281.0355 -165.0817 1431.666 276.0981 -171.7195 1419.183 238.9645 -165.0817 1431.666 240.7681 -172.1813 1418.314 277.594 -164.6233 1432.529 272.9254 -171.3402 1419.896 274.1174 -164.247 1433.236 269.7214 -171.0442 1420.453 245.8826 -164.247 1433.236 242.406 -164.6233 1432.529 247.0746 -171.3402 1419.896 243.9019 -171.7195 1419.183 190.2189 -185.5932 1393.09 331.4111 -187.2688 1389.939 329.7811 -185.5932 1393.09 250.2786 -171.0442 1420.453 249.3873 -163.9535 1433.788 197.0041 -198.5832 1368.66 187.1012 -188.9814 1386.718 188.589 -187.2688 1389.939 332.8988 -188.9814 1386.718 334.2413 -190.7276 1383.434 270.6127 -163.9535 1433.788 267.0869 -163.7434 1434.183 266.494 -170.8323 1420.851 253.506 -170.8323 1420.851 181.8894 -197.9777 1369.798 181.307 -199.8385 1366.299 339.1188 -201.7113 1362.776 338.693 -199.8385 1366.299 263.547 -163.6173 1434.421 263.251 -170.705 1421.091 252.9131 -163.7434 1434.183 256.7491 -170.705 1421.091 185.7587 -190.7276 1383.434 180.8812 -201.7113 1362.776 339.3869 -203.5924 1359.239 335.436 -192.5038 1380.093 260 -163.5752 1434.5 260 -170.6625 1421.171 256.453 -163.6173 1434.421 184.564 -192.5038 1380.093 180.503 -205.4779 1355.692 180.5513 -207.3641 1352.145 180.6131 -203.5924 1359.239 339.497 -205.4779 1355.692 339.4487 -207.3641 1352.145 336.4804 -194.3067 1376.702 183.5196 -194.3067 1376.702 337.3725 -196.1325 1373.269 182.6275 -196.1325 1373.269 338.1106 -197.9777 1369.798 197.0041 -152.5 1368.66 204.9355 -152.5 1391.694 311.1975 -152.5 1396.921 306.8361 -152.5 1401.743 302.0226 -152.5 1406.114 296.8034 -152.5 1409.992 291.2288 -152.5 1413.338 285.3528 -152.5 1416.121 279.2319 -152.5 1418.314 266.494 -152.5 1420.851 272.9254 -152.5 1419.896 260 -152.5 1421.171 253.506 -152.5 1420.851 247.0746 -152.5 1419.896 240.7681 -152.5 1418.314 234.6473 -152.5 1416.121 228.7712 -152.5 1413.338 223.1966 -152.5 1409.992 217.9774 -152.5 1406.114 213.1639 -152.5 1401.743 208.8025 -152.5 1396.921 207.2251 -152.5 1389.406 210.8962 -152.5 1394.469 235.628 -152.5 1413.095 241.5077 -152.5 1415.225 229.9884 -152.5 1410.392 204.074 -152.5 1384.005 247.5696 -152.5 1416.761 253.754 -152.5 1417.69 224.6446 -152.5 1407.144 201.4739 -152.5 1378.317 199.4505 -152.5 1372.4 299.5302 -152.5 1305.945 294.5989 -152.5 1302.351 309.1038 -152.5 1394.469 304.9488 -152.5 1399.143 260 -152.5 1418 219.6491 -152.5 1403.382 215.0512 -152.5 1399.143 266.0951 -152.5 1292.296 260 -152.5 1292 278.057 -152.5 1294.643 272.133 -152.5 1293.179 289.3429 -152.5 1299.251 283.8117 -152.5 1296.673 304.0907 -152.5 1310 318.5261 -152.5 1378.317 300.3509 -152.5 1403.382 295.3554 -152.5 1407.144 290.0116 -152.5 1410.392 284.372 -152.5 1413.095 278.4923 -152.5 1415.225 272.4304 -152.5 1416.761 266.246 -152.5 1417.69 225.4011 -152.5 1302.351 236.1883 -152.5 1296.673 247.867 -152.5 1293.179 308.2375 -152.5 1314.477 315.926 -152.5 1384.005 220.4698 -152.5 1305.945 230.6571 -152.5 1299.251 241.943 -152.5 1294.643 253.9049 -152.5 1292.296 312.7749 -152.5 1389.406 320.5495 -152.5 1372.4 211.7625 -152.5 1314.477 215.9093 -152.5 1310 320.5495 -152.4 1372.4 308.2375 -152.4 1314.477 304.0907 -152.4 1310 304.9488 -152.4 1399.143 300.3509 -152.4 1403.382 315.926 -152.4 1384.005 312.7749 -152.4 1389.406 309.1038 -152.4 1394.469 318.5261 -152.4 1378.317 215.9093 -152.4 1310 229.9884 -152.4 1410.392 224.6446 -152.4 1407.144 295.3554 -152.4 1407.144 201.4739 -152.4 1378.317 199.4505 -152.4 1372.4 211.7625 -152.4 1314.477 235.628 -152.4 1413.095 247.5696 -152.4 1416.761 241.5077 -152.4 1415.225 284.372 -152.4 1413.095 278.4923 -152.4 1415.225 204.074 -152.4 1384.005 219.6491 -152.4 1403.382 215.0512 -152.4 1399.143 260 -152.4 1418 253.754 -152.4 1417.69 272.4304 -152.4 1416.761 266.246 -152.4 1417.69 290.0116 -152.4 1410.392 299.5302 -152.4 1305.945 289.3429 -152.4 1299.251 294.5989 -152.4 1302.351 278.057 -152.4 1294.643 283.8117 -152.4 1296.673 266.0951 -152.4 1292.296 272.133 -152.4 1293.179 207.2251 -152.4 1389.406 210.8962 -152.4 1394.469 253.9049 -152.4 1292.296 260 -152.4 1292 241.943 -152.4 1294.643 247.867 -152.4 1293.179 230.6571 -152.4 1299.251 236.1883 -152.4 1296.673 220.4698 -152.4 1305.945 225.4011 -152.4 1302.351 272.6494 -130.5 1199.792 294.5519 -130.5 1253.367 254.8004 -130.5 1247.78 294.1288 -130.5 1202.811 252.5098 -130.5 1204.072 308.2865 -130.5 1213.479 294.5519 -77 1253.367 254.8004 -77 1247.78 272.6494 -77 1199.792 252.5098 -77 1204.072 308.2865 -77 1213.479 294.1288 -77 1202.811 250.8025 -148.9976 1433.966 249.3874 -150.4128 1433.788 256.453 -148.9976 1434.421 263.547 -148.9976 1434.421 269.1975 -148.9976 1433.966 249.3025 -150.4976 1433.777 249.3025 -162.2976 1433.777 249.3873 -162.3825 1433.788 256.453 -163.4976 1434.421 250.5025 -163.4976 1433.931 263.547 -163.4976 1434.421 269.4975 -163.4976 1433.931 270.6127 -162.3825 1433.788 270.6975 -162.2976 1433.777 270.6975 -150.4976 1433.777 270.6127 -150.4128 1433.788 249.3025 -150.4976 1437 249.3025 -162.2976 1437 270.6975 -150.4976 1437 270.6975 -162.2976 1437 251.0698 -148.9976 1439.201 251.856 -148.9976 1441.274 266.8844 -148.9976 1443.099 268.144 -148.9976 1441.274 253.1156 -148.9976 1443.099 254.7752 -148.9976 1444.569 250.8025 -148.9976 1437 265.2248 -148.9976 1444.569 261.1087 -148.9976 1446.13 263.2615 -148.9976 1445.6 256.7385 -148.9976 1445.6 258.8914 -148.9976 1446.13 268.9302 -148.9976 1439.201 269.1975 -148.9976 1437 270.3866 -150.4976 1439.56 268.0072 -150.4976 1444.094 269.4722 -150.4976 1441.971 266.0769 -150.4976 1445.804 261.2894 -150.4976 1447.619 263.7934 -150.4976 1447.002 258.7106 -150.4976 1447.619 253.9231 -150.4976 1445.804 256.2066 -150.4976 1447.002 251.9928 -150.4976 1444.094 249.6134 -150.4976 1439.56 250.5278 -150.4976 1441.971 270.3866 -162.2976 1439.56 269.4722 -162.2976 1441.971 268.0072 -162.2976 1444.094 266.0769 -162.2976 1445.804 263.7934 -162.2976 1447.002 261.2894 -162.2976 1447.619 258.7106 -162.2976 1447.619 256.2066 -162.2976 1447.002 253.9231 -162.2976 1445.804 251.9928 -162.2976 1444.094 250.5278 -162.2976 1441.971 249.6134 -162.2976 1439.56 254.6048 -163.4976 1444.816 252.891 -163.4976 1443.298 251.5904 -163.4976 1441.414 267.109 -163.4976 1443.298 265.3952 -163.4976 1444.816 250.7785 -163.4976 1439.273 268.4096 -163.4976 1441.414 269.4975 -163.4976 1437 269.2215 -163.4976 1439.273 261.1448 -163.4976 1446.428 258.8552 -163.4976 1446.428 263.3679 -163.4976 1445.88 256.6322 -163.4976 1445.88 250.5025 -163.4976 1437 + + + + + + + + + + 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 -0.1564378 0 0.9876878 -0.4539822 0 0.8910108 -0.7071184 0 0.7070952 -0.8910108 0 0.4539822 -0.9876876 0 0.1564396 -0.9876876 0 -0.1564396 -0.8910108 0 -0.4539822 -0.7071184 0 -0.7070952 -0.4539822 0 -0.8910108 -0.1564378 0 -0.9876878 0.1564378 0 -0.9876878 0.4539822 0 -0.8910108 0.7071184 0 -0.7070952 0.8910108 0 -0.4539822 0.9876876 0 -0.1564396 0.9876876 0 0.1564396 0.8910108 0 0.4539822 0.7071184 0 0.7070952 0.4539822 0 0.8910108 0.1564378 0 0.9876878 0.1564378 0 0.9876878 0.4539822 0 0.8910108 0.7071184 0 0.7070952 0.8910108 0 0.4539822 0.9876876 0 0.1564396 0.9876876 0 -0.1564396 0.8910108 0 -0.4539822 0.7071184 0 -0.7070952 0.4539822 0 -0.8910108 0.1564378 0 -0.9876878 -0.1564378 0 -0.9876878 -0.4539822 0 -0.8910108 -0.7071184 0 -0.7070952 -0.8910108 0 -0.4539822 -0.9876876 0 -0.1564396 -0.9876876 0 0.1564396 -0.8910108 0 0.4539822 -0.7071184 0 0.7070952 -0.4539822 0 0.8910108 -0.1564378 0 0.9876878 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 -1 0 0 -1 0 0 0 0 1 0 0 1 1 0 0 1 0 0 -0.156436 0 0.9876881 -0.4539915 0 0.8910061 -0.7071184 0 0.7070952 -0.8910014 0 0.4540006 -0.9876876 0 0.1564396 -0.9876876 0 -0.1564396 -0.8910014 0 -0.4540006 -0.7071184 0 -0.7070952 -0.4539915 0 -0.8910061 -0.156436 0 -0.9876881 0.156436 0 -0.9876881 0.4539915 0 -0.8910061 0.7071184 0 -0.7070952 0.8910014 0 -0.4540006 0.9876876 0 -0.1564396 0.9876876 0 0.1564396 0.8910014 0 0.4540006 0.7071184 0 0.7070952 0.4539915 0 0.8910061 0.156436 0 0.9876881 0.156436 0 0.9876881 0.4539915 0 0.8910061 0.7071184 0 0.7070952 0.8910014 0 0.4540006 0.9876876 0 0.1564396 0.9876876 0 -0.1564396 0.8910014 0 -0.4540006 0.7071184 0 -0.7070952 0.4539915 0 -0.8910061 0.156436 0 -0.9876881 -0.156436 0 -0.9876881 -0.4539915 0 -0.8910061 -0.7071184 0 -0.7070952 -0.8910014 0 -0.4540006 -0.9876876 0 -0.1564396 -0.9876876 0 0.1564396 -0.8910014 0 0.4540006 -0.7071184 0 0.7070952 -0.4539915 0 0.8910061 -0.156436 0 0.9876881 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 -0.9848078 -0.1736479 0 -0.9848078 -0.1736479 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -0.9986295 0.05233567 0 -0.9986295 0.05233567 -0.9861594 -0.164444 0.02116316 -0.9861593 -0.164444 0.02116316 -0.9861593 -0.164444 0.02116316 -0.9861594 -0.164444 0.0211631 0.9861593 -0.1644441 0.02116298 0.9861593 -0.1644442 0.0211634 0.9861594 -0.1644439 0.02116316 0.9861593 -0.164444 0.02116292 -0.9856622 -0.164361 0.03815132 -0.9856622 -0.1643611 0.03815102 -0.9856622 -0.1643612 0.03815102 -0.9856622 -0.1643611 0.03815096 -0.9856621 -0.1643613 0.0381512 -0.9856626 -0.1643591 0.03815108 -0.971395 -0.1619821 0.1736482 -0.9713968 -0.1619822 0.1736376 0.9856622 -0.1643611 0.03815102 0.9856622 -0.1643608 0.03815078 0.9856622 -0.1643611 0.03815102 0.9856617 -0.164364 0.03815108 0.9856622 -0.1643612 0.03815114 0.9856622 -0.1643612 0.03815126 0.9713938 -0.1619819 0.1736551 0.971395 -0.1619819 0.1736481 -0.9998477 0 0.01745247 -0.9998477 0 0.017452 -0.9998477 0 0.01745247 -0.9998477 -2.76141e-7 0.01745235 -0.9998477 0 0.01745223 0.9998477 2.22186e-7 0.01745229 0.9998477 1.30804e-7 0.01745229 0.9998477 4.29827e-7 0.01745319 0.9998477 0 0.01745802 0.9998477 0 0.01745229 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 -0.9982239 0 -0.05957591 -0.9999994 0 -0.001120507 -0.9983547 0 0.05734086 -0.9983547 0 0.05734086 -0.9999994 0 -0.001120507 -0.9982239 0 -0.05957591 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 -0.632678 0 -0.774415 -0.6978086 0 -0.7162843 -0.9972006 0 0.07477289 -0.9868783 0 0.1614659 -0.7576037 0.007055759 -0.6526768 -0.7384271 0 -0.6743333 -0.7384272 0 -0.6743333 -0.8116636 0 -0.5841253 -0.8595179 0 -0.5111057 -0.9008207 0 -0.4341913 -0.9352586 0 -0.3539654 -0.9625673 0 -0.271043 -0.9825384 0 -0.1860594 -0.9950224 0 -0.09965097 -0.9998529 0 0.01714855 -0.9996486 0 -0.02650916 -0.9998984 0.006875932 -0.0124852 -0.999853 0 0.01714855 -0.9950224 0 -0.09965097 -0.9825384 0 -0.1860594 -0.9625673 0 -0.271043 -0.9352586 0 -0.3539654 -0.9008207 0 -0.4341913 -0.8595179 0 -0.5111057 -0.8116636 0 -0.5841253 -0.7671676 0 -0.6414467 -0.9868783 0 0.1614659 -0.9972006 0 0.07477289 -0.6978086 0 -0.7162843 -0.632678 0 -0.774415 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0.3420214 -6.0945e-7 -0.9396922 0.3420199 0 -0.9396927 0.3420199 0 -0.9396927 0.3420218 0 -0.9396919 -0.642787 0 0.7660449 -0.6427896 0 0.7660429 -0.642789 5.10128e-6 0.7660434 -0.6427871 0 0.7660449 -0.6990643 0 -0.7150589 -0.7506631 0 -0.6606852 -0.7980384 0 -0.6026067 -0.7980384 0 -0.6026067 -0.7506631 0 -0.6606852 -0.6990643 0 -0.7150589 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0.9983549 0 0.05733644 0.9999994 0 -0.001125931 0.9982233 0 -0.0595836 0.9982233 0 -0.0595836 0.9999994 0 -0.001125931 0.9983549 0 0.05733644 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 -7.59803e-5 0 -1 -8.91704e-5 0 -1 -8.63931e-5 -2.09115e-5 -1 -7.59803e-5 0 -1 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0.986878 0 0.161468 0.9972006 0 0.07477289 0.6978086 0 -0.7162843 0.632678 0 -0.774415 0.9998983 0.006879508 -0.01248729 0.9998533 0 0.01713055 0.9998534 0 0.01713055 0.9950224 0 -0.09965097 0.9825393 0 -0.1860554 0.9625667 0 -0.2710449 0.9352586 0 -0.3539654 0.9008207 0 -0.4341913 0.8595169 0 -0.5111073 0.8116645 0 -0.5841239 0.7384352 0 -0.6743245 0.7671781 0 -0.6414343 0.7576037 0.007059931 -0.6526767 0.7384352 0 -0.6743245 0.8116645 0 -0.5841239 0.8595169 0 -0.5111073 0.9008207 0 -0.4341913 0.9352586 0 -0.3539654 0.9625667 0 -0.2710449 0.9825393 0 -0.1860554 0.9950224 0 -0.09965097 0.9996481 0 -0.02652549 0.632678 0 -0.774415 0.6978086 0 -0.7162843 0.9972006 0 0.07477289 0.986878 0 0.161468 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 -0.3420199 0 -0.9396927 -0.3420218 0 -0.9396919 -0.3420214 -6.0945e-7 -0.9396922 -0.3420199 0 -0.9396927 0.6427887 -6.24636e-7 0.7660436 0.642789 0 0.7660433 0.642789 0 0.7660434 0.6427887 0 0.7660436 0.798054 0 -0.6025858 0.7506676 0 -0.6606802 0.6990696 0 -0.7150537 0.6990696 0 -0.7150537 0.7506676 0 -0.6606802 0.798054 0 -0.6025858 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 -0.976781 -0.1628801 -0.139173 -0.9767809 -0.1628802 -0.1391732 -0.976781 -0.1628802 -0.1391722 -0.9767808 -0.1628803 -0.1391734 0.9767808 -0.1628803 -0.1391734 0.976781 -0.1628801 -0.139173 0.9767809 -0.1628802 -0.1391732 0.9767797 -0.1628802 -0.1391807 -0.9998477 0 0.01745241 -0.9998477 0 0.01745188 -0.9998477 0 0.01745051 -0.9998477 0 0.01745241 0.9998477 0 0.01745051 0.9998477 0 0.01745253 0.9998477 1.33576e-7 0.01745259 0.9998477 0 0.01745265 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 -0.04424124 0 0.9990209 -0.1323444 0 0.9912037 -0.2194467 0 0.9756245 -0.3047913 0 0.9524191 -0.3877887 0 0.9217483 -0.4677461 0 0.8838629 -0.5440093 0 0.8390792 -0.6160489 0 0.787708 -0.6832604 0 0.7301748 -0.745116 0 0.6669349 -0.8011411 0 0.5984756 -0.8509011 0 0.5253258 -0.8939999 0 0.4480671 -0.9301018 0 0.3673018 -0.9589243 0 0.2836619 -0.9802423 0 0.1978008 -0.9938881 0 0.1103925 -0.9997553 0 0.02212291 -0.9977982 0 -0.06632292 0.9977985 0 -0.06631863 0.9997554 0 0.02212077 0.9938883 0 0.1103903 0.9802414 0 0.1978049 0.9589243 0 0.2836619 0.9301018 0 0.3673018 0.8940008 0 0.4480655 0.8509011 0 0.5253258 0.8011411 0 0.5984756 0.745116 0 0.6669349 0.6832604 0 0.7301748 0.6160498 0 0.7877071 0.5440073 0 0.8390804 0.467747 0 0.8838624 0.3877878 0 0.9217486 0.3047927 0 0.9524188 0.2194463 0 0.9756246 0.1323444 0 0.9912037 0.04424124 0 0.9990209 0.9705339 0 -0.2409647 0.9454375 0 -0.3258037 0.9129449 0 -0.4080827 0.8733039 0 -0.4871758 0.826835 0 -0.5624446 0.7738848 0 -0.6333263 0.7148834 0 -0.6992437 0.6502877 0 -0.759688 0.5806041 0 -0.814186 0.5063687 0 -0.862317 0.4281836 0 -0.9036917 0.346634 0 -0.9380005 0.2623777 0 -0.9649652 0.1760683 0 -0.9843779 0.08839601 0 -0.9960855 0 -0.005795955 -0.9999832 -0.02210658 0 -0.9997557 -0.08839619 0 -0.9960854 -0.176068 0 -0.984378 -0.2623777 0 -0.9649652 -0.3466346 0 -0.9380002 -0.428182 0 -0.9036925 -0.5063697 0 -0.8623165 -0.5806041 0 -0.814186 -0.6502877 0 -0.759688 -0.7148823 0 -0.6992447 -0.773887 0 -0.6333237 -0.826833 0 -0.5624476 -0.8733058 0 -0.4871726 -0.9129434 0 -0.4080864 -0.9454381 0 -0.3258017 -0.9705343 0 -0.2409627 -0.9927022 0 -0.1205915 -0.9863981 0 -0.1643744 -0.9880232 0.004130065 -0.1542498 0.9880232 0.004128932 -0.1542498 0.9927011 0 -0.1206007 0.9927011 0 -0.1206007 0.9863985 0 -0.1643717 -0.9927021 0 -0.1205915 -0.9705343 0 -0.2409627 -0.9454381 0 -0.3258017 -0.9129434 0 -0.4080864 -0.8733058 0 -0.4871726 -0.826833 0 -0.5624476 -0.773887 0 -0.6333237 -0.7148823 0 -0.6992447 -0.6502877 0 -0.759688 -0.5806041 0 -0.814186 -0.5063697 0 -0.8623165 -0.428182 0 -0.9036925 -0.3466346 0 -0.9380002 -0.2623777 0 -0.9649652 -0.176068 0 -0.984378 -0.08839619 0 -0.9960854 0.02210658 0 -0.9997557 0.08839601 0 -0.9960855 0.1760683 0 -0.9843779 0.2623777 0 -0.9649652 0.346634 0 -0.9380005 0.4281836 0 -0.9036917 0.5063687 0 -0.862317 0.5806041 0 -0.814186 0.6502877 0 -0.759688 0.7148834 0 -0.6992437 0.7738848 0 -0.6333263 0.826835 0 -0.5624446 0.8733039 0 -0.4871758 0.9129449 0 -0.4080827 0.9454375 0 -0.3258037 0.9705339 0 -0.2409647 0.04424124 0 0.9990209 0.1323444 0 0.9912037 0.2194463 0 0.9756246 0.3047927 0 0.9524188 0.3877878 0 0.9217486 0.467747 0 0.8838624 0.5440073 0 0.8390804 0.6160498 0 0.7877071 0.6832604 0 0.7301748 0.745116 0 0.6669349 0.8011411 0 0.5984756 0.8509011 0 0.5253258 0.8940008 0 0.4480655 0.9301018 0 0.3673018 0.9589243 0 0.2836619 0.9802414 0 0.1978049 0.9938883 0 0.1103903 0.9997554 0 0.02212077 0.9977985 0 -0.06631863 -0.9977982 0 -0.06632292 -0.9997553 0 0.02212291 -0.9938881 0 0.1103925 -0.9802423 0 0.1978008 -0.9589243 0 0.2836619 -0.9301018 0 0.3673018 -0.8939999 0 0.4480671 -0.8509011 0 0.5253258 -0.8011411 0 0.5984756 -0.745116 0 0.6669349 -0.6832604 0 0.7301748 -0.6160489 0 0.787708 -0.5440093 0 0.8390792 -0.4677461 0 0.8838629 -0.3877887 0 0.9217483 -0.3047913 0 0.9524191 -0.2194467 0 0.9756245 -0.1323444 0 0.9912037 -0.04424124 0 0.9990209 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0.2656136 0 0.9640796 0.3445153 0 0.9387808 0.4210661 0 0.9070299 0.4947149 0 0.8690554 0.5649663 0 0.825114 0.6313419 0 0.7755046 0.6933842 0 0.7205681 0.7506627 0 0.6606856 0.8027848 0 0.5962689 0.8493963 0 0.5277554 0.8901771 0 0.4556148 0.9248406 0 0.3803548 0.9531573 0 0.3024752 0.9749291 0 0.2225159 0.9900041 0 0.1410383 0.9982821 7.13083e-4 0.05858486 0.995468 0 0.09509664 0.995468 0 0.09509664 0.9997056 0 -0.02426576 0.994264 0 -0.1069546 0.9819949 0 -0.1889071 0.962984 0 -0.2695586 0.9373576 0 -0.3483686 0.9052995 0 -0.4247739 0.8670194 0 -0.4982743 0.8227897 0 -0.568346 0.772909 0 -0.634517 0.7177201 0 -0.6963317 0.9996613 0 0.02602511 0.9990495 0.002775847 -0.04350352 0.9999937 0 -0.00354439 0.9920296 0.002988815 -0.1259697 0.9962666 0 -0.08632928 0.9927253 0 -0.1204015 0.9927253 0 -0.1204015 0.9781771 0.002878785 -0.2077526 0.9856991 0 -0.1685155 0.9576433 0.003103792 -0.2879403 0.9683626 0 -0.2495476 0.9305431 0.00336194 -0.3661671 0.9443745 0 -0.3288721 0.897069 0.003658652 -0.4418754 0.9139069 0 -0.4059237 0.8574418 0.003998279 -0.5145653 0.8771563 0 -0.4802049 0.834159 0 -0.5515241 0.8108198 -5.49796e-5 -0.5852959 0.8344063 5.82323e-5 -0.5511498 0.8105904 0 -0.5856136 0.7591454 0.006785213 -0.6508857 0.7844547 0 -0.6201862 0.7041921 0.006583929 -0.7099789 0.7319934 0 -0.6813117 0.6417919 -3.45503e-4 -0.7668787 0.6730819 0 -0.7395679 0.6401898 0 -0.7682169 0.6401898 0 -0.7682169 0.6714637 0 -0.7410374 0.6576049 0.001717031 -0.753361 0.5764492 0.001920759 -0.8171309 0.6095293 0 -0.7927635 0.5067888 0.001955926 -0.8620681 0.5418087 0 -0.8405019 0.4336389 0.00198704 -0.9010846 0.4703454 0 -0.8824824 0.3575077 0.002015292 -0.933908 0.3956677 0 -0.9183936 0.2789078 0.002039611 -0.9603157 0.3182687 0 -0.9480005 0.1983897 0.002059578 -0.9801211 0.2386912 0 -0.9710955 0.1164935 0.002075195 -0.9931893 0.1574766 0 -0.9875227 0.05449694 0.001042902 -0.9985134 0.07517719 0 -0.9971702 -0.007655262 0 -0.9999707 -0.02836954 0.001043021 -0.9995969 -0.1110258 0 -0.9938176 -0.09046792 0.002078413 -0.9958972 -0.1929292 0 -0.9812126 -0.1726738 0.002064824 -0.9849769 -0.2735059 0 -0.9618703 -0.2536786 0.002047121 -0.9672864 -0.3522038 0 -0.9359233 -0.3329432 0.002023875 -0.9429447 -0.4284882 0 -0.9035474 -0.4099194 0.001996576 -0.9121196 -0.5018219 0 -0.8649709 -0.4840604 0.001966059 -0.8750324 -0.5717146 0 -0.8204526 -0.5548732 0.00193268 -0.8319327 -0.999916 0 0.01296567 -0.9987291 0 -0.05040144 -0.9975721 0.002839803 -0.06958389 -0.991067 0 -0.1333648 -0.9957217 -0.006570041 -0.09216898 -0.9884014 0.003062963 -0.1518337 -0.9936688 0 -0.1123493 -0.9767194 0 -0.2145211 -0.9724167 0.002946197 -0.2332319 -0.9556056 0 -0.294649 -0.9497937 0.003181576 -0.3128604 -0.9279289 0 -0.3727571 -0.9206613 0.003450989 -0.390347 -0.893881 0 -0.4483044 -0.8852186 0.003760457 -0.4651601 -0.8536944 0 -0.5207745 -0.8437076 0.004115402 -0.5367874 -0.8028583 0 -0.5961698 -0.7959594 0.002750217 -0.6053439 -0.8268623 0 -0.5624046 -0.8268622 0 -0.5624045 -0.756051 0 -0.6545129 -0.7499661 0.003004491 -0.6614695 -0.6992673 0 -0.7148604 -0.68538 0.006747782 -0.7281544 -0.6376789 0.001255452 -0.7703013 -0.6300865 0 -0.776525 -0.6300865 0 -0.776525 -0.6617107 -0.001985013 -0.7497566 -0.6220421 0.002979278 -0.7829782 -0.6535108 0 -0.7569172 -0.6992672 0 -0.7148603 -0.7560509 0 -0.6545128 -0.8076469 0 -0.5896665 -0.8536943 0 -0.5207744 -0.893881 0 -0.4483044 -0.9279289 0 -0.3727572 -0.9556055 0 -0.294649 -0.9767194 0 -0.2145211 -0.9911273 0 -0.1329157 -0.9987291 0 -0.05040144 -0.9994729 0 0.03246301 -0.992369 0 0.1233032 -0.9966257 0 0.08208113 -0.9933531 0.001108348 0.1151017 -0.9804136 0 0.19695 -0.9607418 0 0.2774441 -0.9344714 0 0.356038 -0.9017841 0 0.4321867 -0.8629063 0 0.505364 -0.8181039 0 0.5750705 -0.767683 0 0.6408298 -0.7119857 0 0.702194 -0.6514074 0 0.7587281 -0.5863491 0 0.8100585 -0.5172724 0 0.8558208 -0.4446378 0 0.8957104 -0.36895 0 0.9294492 -0.2907294 0 0.9568053 -0.2105174 0 0.9775902 -0.1288491 0 0.9916643 -0.1288491 0 0.9916643 -0.2105174 0 0.9775902 -0.2907294 0 0.9568053 -0.36895 0 0.9294492 -0.4446378 0 0.8957104 -0.5172724 0 0.8558208 -0.5863491 0 0.8100585 -0.6514074 0 0.7587281 -0.7119857 0 0.702194 -0.767683 0 0.6408298 -0.8181039 0 0.5750705 -0.8629063 0 0.505364 -0.9017841 0 0.4321867 -0.9344714 0 0.356038 -0.9607418 0 0.2774441 -0.9804136 0 0.19695 -0.9923691 0 0.1233032 -0.9994729 0 0.03246301 -0.9987291 0 -0.05040144 -0.9911273 0 -0.1329157 -0.9767194 0 -0.2145211 -0.9556055 0 -0.294649 -0.9279289 0 -0.3727572 -0.893881 0 -0.4483044 -0.8536943 0 -0.5207744 -0.8076469 0 -0.5896665 -0.7560509 0 -0.6545128 -0.6992672 0 -0.7148603 -0.6617121 0 -0.7497581 -0.7139317 0 -0.7002153 -0.7762744 0 -0.6303951 -0.8195231 -6.65058e-4 -0.5730457 -0.8642992 0 -0.5029782 -0.9029775 0 -0.4296879 -0.9354531 0 -0.3534511 -0.9615058 0 -0.2747848 -0.9809547 0 -0.1942366 -0.991067 0 -0.1333649 -0.9995591 0 -0.02969461 -0.9999159 0 0.01296567 -0.5885989 0 -0.8084253 -0.5196375 0 -0.8543868 -0.4471148 0 -0.8944765 -0.371519 0 -0.9284253 -0.2933784 0 -0.9559964 -0.2132154 0 -0.9770053 -0.1315965 0 -0.9913033 -0.04907184 0 -0.9987952 0.03379333 0 -0.9994289 0.1369756 0 -0.9905744 0.2185225 0 -0.9758319 0.2985639 0 -0.9543896 0.3765595 0 -0.9263924 0.4519633 0 -0.8920365 0.524273 0 -0.8515502 0.5929701 0 -0.8052245 0.6714637 3.89149e-4 -0.7410373 0.7177202 0 -0.6963317 0.772909 0 -0.6345169 0.834159 0 -0.5515241 0.8670195 0 -0.4982743 0.9052994 0 -0.4247739 0.9373576 0 -0.3483686 0.962984 0 -0.2695586 0.981995 0 -0.1889071 0.9968523 -0.004357218 -0.07916188 0.9997055 0 -0.02426576 0.9996613 0 0.02602511 0.7177201 0 -0.6963317 0.772909 0 -0.634517 0.8227897 0 -0.568346 0.8670194 0 -0.4982743 0.9052995 0 -0.4247739 0.9373576 0 -0.3483686 0.962984 0 -0.2695586 0.9819949 0 -0.1889071 0.994264 0 -0.1069546 0.9997056 0 -0.02426576 0.9985529 0 0.05377793 0.9900041 0 0.1410383 0.9749291 0 0.2225159 0.9531573 0 0.3024752 0.9248406 0 0.3803548 0.8901771 0 0.4556148 0.8493963 0 0.5277554 0.8027848 0 0.5962689 0.7506627 0 0.6606856 0.6933842 0 0.7205681 0.6313419 0 0.7755046 0.5649663 0 0.825114 0.4947149 0 0.8690554 0.4210661 0 0.9070299 0.3445153 0 0.9387808 0.2656136 0 0.9640796 2.04521e-6 -0.9510568 -0.3090162 -2.78986e-7 -0.951056 -0.3090187 0 -0.9510552 -0.3090213 -5.81302e-6 -0.9510575 -0.3090139 -2.63093e-6 -0.9510563 -0.3090177 3.88181e-7 -0.9510563 -0.3090177 -1.89006e-6 -0.9510567 -0.3090166 2.79587e-6 -0.9510564 -0.3090175 -1.51818e-6 -0.9510573 -0.3090146 2.33734e-6 -0.951057 -0.3090158 -1.41469e-6 -0.9510564 -0.3090173 8.67804e-7 -0.9510561 -0.3090183 3.16665e-6 -0.9510562 -0.3090181 -1.41179e-6 -0.9510573 -0.3090147 0 -0.9510561 -0.3090184 -4.05183e-7 -0.9510568 -0.3090164 5.56597e-7 -0.9510568 -0.3090161 0 -0.9510547 -0.3090224 3.15501e-6 -0.9510554 -0.3090203 -8.84613e-7 -0.9510561 -0.3090182 -4.77758e-7 -0.951056 -0.3090184 -1.64267e-6 -0.9510562 -0.3090178 2.73276e-6 -0.9510568 -0.3090161 2.83825e-6 -0.9510574 -0.3090144 -7.88073e-7 -0.9510561 -0.3090183 1.17489e-6 -0.951056 -0.3090186 3.88255e-6 -0.9510568 -0.3090164 2.20827e-6 -0.951057 -0.3090153 -4.16628e-7 -0.9510563 -0.3090178 -2.97163e-6 -0.9510562 -0.3090181 -5.4325e-6 -0.9510579 -0.3090129 -1.59707e-6 -0.9510567 -0.3090162 -1.09473e-6 -0.9510566 -0.309017 3.31924e-7 -0.9510565 -0.3090172 1.51692e-6 -0.9510568 -0.3090161 1.36621e-6 -0.9510566 -0.3090167 -4.40895e-7 -0.9510564 -0.3090171 5.87754e-7 -0.9510566 -0.3090168 4.07145e-6 -0.9510565 -0.309017 3.75164e-6 -0.9510571 -0.309015 -2.67196e-7 -0.9510563 -0.3090177 -3.43284e-6 -0.951056 -0.3090188 -4.43286e-7 -0.9510567 -0.3090162 -2.28764e-7 -0.9510563 -0.3090177 -2.72003e-6 -0.9510564 -0.3090173 -1.4587e-6 -0.9510563 -0.309018 2.35322e-7 -0.9510563 -0.3090177 6.95502e-7 -0.9510568 -0.3090163 -7.78952e-7 -0.9510564 -0.3090175 -9.32858e-7 -0.9510565 -0.3090168 -2.50104e-6 -0.951056 -0.3090186 2.72714e-6 -0.9510573 -0.3090148 8.89924e-7 -0.9510567 -0.3090165 -2.90738e-6 -0.9510562 -0.3090181 3.68967e-6 -0.9510561 -0.3090185 2.27991e-6 -0.9510566 -0.3090168 -2.25674e-6 -0.9510564 -0.3090173 -1.11899e-6 -0.9510563 -0.3090178 -2.86598e-6 -0.951057 -0.3090155 -5.83808e-7 -0.9510567 -0.3090164 0 -0.9510564 -0.3090177 -6.951e-7 -0.9510563 -0.309018 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 0 1 0 0 1 -0.9876884 0 -0.1564345 -0.9876886 0 -0.1564335 -0.9876884 -1.5205e-7 -0.1564344 -0.9876884 0 -0.1564345 0.9563047 -2.19286e-7 -0.2923715 0.9563047 0 -0.2923718 0.9563047 0 -0.2923718 0.9563059 0 -0.292368 -0.9781476 0 0.2079115 -0.9781476 0 0.2079115 -0.6293118 0 0.777153 -0.6293118 0 0.777153 0 0 1 0 0 1 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0.8386706 0 0.5446391 0.8386706 0 0.5446391 0.4771579 0 0.8788177 0.4771579 0 0.8788177 0.9902681 0 0.1391729 0.9902681 0 0.1391729 -1.12262e-6 -0.8829478 -0.4694713 -1.15755e-6 -0.8829469 -0.469473 -2.35057e-6 -0.8829495 -0.4694679 -1.69109e-6 -0.88295 -0.4694669 -2.60011e-7 -0.8829491 -0.4694687 -3.99442e-6 -0.8829493 -0.4694684 -1.4706e-6 -0.8829485 -0.4694697 -3.07018e-7 -0.8829467 -0.4694733 2.37659e-6 -0.8829456 -0.4694752 0 -0.8829476 -0.4694713 0 -0.8829476 -0.4694718 -3.00453e-6 -0.8829473 -0.4694722 -5.55463e-6 -0.8829458 -0.469475 -3.72085e-6 -0.8829471 -0.4694724 3.23713e-6 -0.8829491 -0.4694687 -4.77877e-7 -0.8829481 -0.4694705 -2.75925e-7 -0.8829475 -0.4694718 1.96273e-6 -0.8829494 -0.4694684 -6.53944e-6 -0.8829439 -0.4694786 -2.73277e-7 -0.8829476 -0.4694716 -2.10561e-6 -0.8829461 -0.4694744 0 -0.8829476 -0.4694717 -5.06845e-7 -0.8829478 -0.4694712 0 -0.8829495 -0.4694681 -1 0 0 -1 0 0 -0.9063079 0 0.4226181 -0.9063079 0 0.422618 0.7249436 -0.007343113 0.688769 0.7535511 0 0.6573894 0.6825289 0 0.7308586 0.6153628 0 0.788244 0.5433822 0 0.8394854 0.4671649 0 0.8841702 0.3873044 0 0.9219518 0.3044174 0 0.9525388 0.2191513 0 0.975691 0.1321856 0 0.991225 0.04417026 0 0.999024 -0.04417026 0 0.9990241 -0.1321856 0 0.991225 -0.2191517 0 0.9756908 -0.3044167 0 0.9525389 -0.3873035 0 0.9219523 -0.4671658 0 0.8841696 -0.5433823 0 0.8394855 -0.6153628 0 0.788244 -0.6825277 0 0.7308598 -0.7443791 0 0.6677573 -0.7249438 -0.00734353 0.6887689 -0.7535528 0 0.6573876 -0.6825278 0 0.7308598 -0.6153628 0 0.788244 -0.5433822 0 0.8394854 -0.4671658 0 0.8841697 -0.3873035 0 0.9219523 -0.3044168 0 0.952539 -0.2191517 0 0.9756909 -0.1321856 0 0.991225 -0.04417026 0 0.999024 0.04417026 0 0.9990241 0.1321856 0 0.991225 0.2191513 0 0.975691 0.3044174 0 0.9525387 0.3873044 0 0.921952 0.4671649 0 0.8841702 0.5433823 0 0.8394855 0.6153628 0 0.788244 0.6825289 0 0.7308586 0.7443779 0 0.6677586 -0.9895621 0 -0.1441066 -0.9895622 1.22799e-7 -0.1441067 -0.9895623 0 -0.1441055 -0.9238801 0 -0.3826822 -0.9238801 0 -0.3826822 -0.7071068 0 -0.7071068 -0.7071068 0 -0.7071068 -0.3826839 0 -0.9238793 -0.3826839 0 -0.9238794 0 0 -1 0 0 -1 0.3826839 0 -0.9238794 0.3826839 0 -0.9238793 0.7071068 0 -0.7071068 0.7071068 0 -0.7071068 0 -0.9396936 -0.3420175 -8.86971e-7 -0.9396927 -0.34202 3.69631e-7 -0.9396927 -0.3420202 -3.6963e-7 -0.9396926 -0.3420202 -3.52388e-7 -0.9396926 -0.3420202 -3.43069e-7 -0.9396926 -0.3420202 0 -0.9396936 -0.3420175 -1.56824e-7 -0.9396925 -0.3420205 0 -0.9396922 -0.3420213 8.8697e-7 -0.9396927 -0.34202 0 -0.9396921 -0.3420213 3.43069e-7 -0.9396926 -0.3420202 1.56824e-7 -0.9396925 -0.3420205 3.52388e-7 -0.9396926 -0.3420202 0.9238797 0 -0.382683 0.9238797 0 -0.382683 1.24043e-6 -0.8829482 -0.4694704 -5.16534e-7 -0.8829454 -0.4694759 -5.83399e-6 -0.8829486 -0.4694697 8.9872e-7 -0.8829476 -0.4694713 8.81554e-7 -0.8829479 -0.469471 -1.53235e-6 -0.8829454 -0.4694757 6.91498e-6 -0.8829465 -0.4694736 4.86414e-6 -0.8829498 -0.4694676 4.11933e-7 -0.8829475 -0.4694718 -2.50088e-6 -0.8829488 -0.4694693 1.95286e-6 -0.8829482 -0.4694705 4.86073e-6 -0.8829461 -0.4694743 -4.39869e-7 -0.8829478 -0.4694712 4.38621e-6 -0.8829452 -0.4694759 -6.55761e-7 -0.8829493 -0.4694685 -1.70293e-6 -0.8829483 -0.4694702 7.34645e-7 -0.8829479 -0.469471 0 -0.8829475 -0.4694716 5.06846e-7 -0.8829478 -0.4694713 2.44274e-7 -0.8829503 -0.4694664 1.06178e-6 -0.8829471 -0.4694727 0 -0.8829495 -0.4694681 1.16967e-6 -0.8829477 -0.4694714 2.73277e-7 -0.8829475 -0.4694716 0.9895622 0 -0.1441065 0.9895621 0 -0.1441069 0.9895621 0 -0.1441066 0.9063079 0 0.422618 0.9063079 0 0.4226181 1 0 0 1 0 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 -0.919569 0 -0.3929286 -0.8789339 0 -0.4769436 -0.8306488 0 -0.5567964 -0.7751201 0 -0.6318139 -0.7128451 0 -0.7013216 -0.6443635 0 -0.7647194 -0.5702661 0 -0.82146 -0.4912067 0 -0.871043 -0.4078701 0 -0.9130399 -0.3209699 0 -0.9470894 -0.2312793 0 -0.9728874 -0.1395802 0 -0.9902108 -0.04666489 0 -0.9989106 0.04666489 0 -0.9989106 0.1395799 0 -0.9902108 0.2312798 0 -0.9728872 0.3209707 0 -0.9470891 0.4078693 0 -0.9130403 0.4912057 0 -0.8710436 0.5702672 0 -0.8214592 0.6443635 0 -0.7647194 0.7128439 0 -0.7013227 0.7751212 0 -0.6318125 0.8306479 0 -0.5567981 0.8789349 0 -0.4769418 0.9195699 0 -0.3929266 0.9195699 0 -0.3929266 0.8789349 0 -0.4769418 0.8306479 0 -0.5567981 0.7751212 0 -0.6318125 0.7128439 0 -0.7013227 0.6443635 0 -0.7647194 0.5702672 0 -0.8214592 0.4912057 0 -0.8710436 0.4078693 0 -0.9130403 0.3209707 0 -0.9470891 0.2312798 0 -0.9728872 0.1395799 0 -0.9902108 0.04666489 0 -0.9989106 -0.04666489 0 -0.9989106 -0.1395802 0 -0.9902108 -0.2312793 0 -0.9728874 -0.3209699 0 -0.9470894 -0.4078701 0 -0.9130399 -0.4912067 0 -0.871043 -0.5702661 0 -0.82146 -0.6443635 0 -0.7647194 -0.7128451 0 -0.7013216 -0.7751201 0 -0.6318139 -0.8306488 0 -0.5567964 -0.8789339 0 -0.4769436 -0.919569 0 -0.3929286 1 0 0 1 0 0 0.9195699 0 0.3929266 0.8789349 0 0.4769418 0.8306479 0 0.5567981 0.7751212 0 0.6318125 0.7128439 0 0.7013227 0.6443635 0 0.7647194 0.5702672 0 0.8214592 0.4912057 0 0.8710436 0.4078693 0 0.9130403 0.3209707 0 0.9470891 0.2312798 0 0.9728872 0.1395799 0 0.9902108 0.04666489 0 0.9989106 -0.04666489 0 0.9989106 -0.1395802 0 0.9902108 -0.2312793 0 0.9728874 -0.3209699 0 0.9470894 -0.4078701 0 0.9130399 -0.4912067 0 0.871043 -0.5702661 0 0.82146 -0.6443635 0 0.7647194 -0.7128451 0 0.7013216 -0.7751201 0 0.6318139 -0.8306488 0 0.5567964 -0.8789339 0 0.4769436 -0.919569 0 0.3929286 -0.919569 0 0.3929286 -0.8789339 0 0.4769436 -0.8306488 0 0.5567964 -0.7751201 0 0.6318139 -0.7128451 0 0.7013216 -0.6443635 0 0.7647194 -0.5702661 0 0.82146 -0.4912067 0 0.871043 -0.4078701 0 0.9130399 -0.3209699 0 0.9470894 -0.2312793 0 0.9728874 -0.1395802 0 0.9902108 -0.04666489 0 0.9989106 0.04666489 0 0.9989106 0.1395799 0 0.9902108 0.2312798 0 0.9728872 0.3209707 0 0.9470891 0.4078693 0 0.9130403 0.4912057 0 0.8710436 0.5702672 0 0.8214592 0.6443635 0 0.7647194 0.7128439 0 0.7013227 0.7751212 0 0.6318125 0.8306479 0 0.5567981 0.8789349 0 0.4769418 0.9195699 0 0.3929266 -1 0 0 -1 0 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -0.9848077 0.1736483 0 -0.9848077 0.1736484 0 -0.9848077 0.1736484 0 -0.9848078 0.1736481 0 -0.9848078 0.173648 0 -0.9848077 0.1736484 0 -0.9848077 0.1736481 0 -0.9848077 0.1736485 0 -0.9848077 0.1736484 0 -0.9848078 0.173648 0 0 1 0 0 1 -1 0 0 1 0 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 -0.1564378 0 0.9876878 -0.4539822 0 0.8910108 -0.707072 0 0.7071416 -0.8910203 0 0.4539633 -0.9876876 0 0.1564396 -0.9876876 0 -0.1564396 -0.8910203 0 -0.4539633 -0.707072 0 -0.7071416 -0.4539822 0 -0.8910108 -0.1564378 0 -0.9876878 0.1564378 0 -0.9876878 0.4539822 0 -0.8910108 0.707072 0 -0.7071416 0.8910203 0 -0.4539633 0.9876876 0 -0.1564396 0.9876876 0 0.1564396 0.8910203 0 0.4539633 0.707072 0 0.7071416 0.4539822 0 0.8910108 0.1564378 0 0.9876878 0.1564378 0 0.9876878 0.4539822 0 0.8910108 0.707072 0 0.7071416 0.8910203 0 0.4539633 0.9876876 0 0.1564396 0.9876876 0 -0.1564396 0.8910203 0 -0.4539633 0.707072 0 -0.7071416 0.4539822 0 -0.8910108 0.1564378 0 -0.9876878 -0.1564378 0 -0.9876878 -0.4539822 0 -0.8910108 -0.707072 0 -0.7071416 -0.8910203 0 -0.4539633 -0.9876876 0 -0.1564396 -0.9876876 0 0.1564396 -0.8910203 0 0.4539633 -0.707072 0 0.7071416 -0.4539822 0 0.8910108 -0.1564378 0 0.9876878 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 -0.156436 0 0.9876881 -0.4539915 0 0.8910061 -0.707072 0 0.7071416 -0.891011 0 0.4539818 -0.9876876 0 0.1564396 -0.9876876 0 -0.1564396 -0.891011 0 -0.4539818 -0.707072 0 -0.7071416 -0.4539915 0 -0.8910061 -0.156436 0 -0.9876881 0.156436 0 -0.9876881 0.4539915 0 -0.8910061 0.707072 0 -0.7071416 0.891011 0 -0.4539818 0.9876876 0 -0.1564396 0.9876876 0 0.1564396 0.891011 0 0.4539818 0.707072 0 0.7071416 0.4539915 0 0.8910061 0.156436 0 0.9876881 0.156436 0 0.9876881 0.4539915 0 0.8910061 0.707072 0 0.7071416 0.891011 0 0.4539818 0.9876876 0 0.1564396 0.9876876 0 -0.1564396 0.891011 0 -0.4539818 0.707072 0 -0.7071416 0.4539915 0 -0.8910061 0.156436 0 -0.9876881 -0.156436 0 -0.9876881 -0.4539915 0 -0.8910061 -0.707072 0 -0.7071416 -0.891011 0 -0.4539818 -0.9876876 0 -0.1564396 -0.9876876 0 0.1564396 -0.891011 0 0.4539818 -0.707072 0 0.7071416 -0.4539915 0 0.8910061 -0.156436 0 0.9876881 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 -9.26886e-7 -0.9563046 0.2923722 -1.78395e-7 -0.9563047 0.2923716 0 -0.9563049 0.2923713 0 -0.9563046 0.2923718 0 -0.9563049 0.2923713 9.26885e-7 -0.9563046 0.2923722 1.78395e-7 -0.9563047 0.2923716 0 -0.9563047 0.2923718 -0.382683 0 0.9238798 -0.3826829 0 0.9238798 0 0 1 0 0 1 0.3826826 0 0.9238799 0.3826827 0 0.9238799 -0.7071268 -5.13104e-6 0.7070868 -0.7071049 0 0.7071088 -0.7071077 0 0.7071059 0.707108 0 0.7071055 0.7071268 -5.02488e-6 0.7070868 0.7071053 0 0.7071083 -0.923879 0 0.3826847 -0.923879 0 0.3826847 -0.9781477 0 0.2079115 -0.9781477 0 0.2079116 -0.9455184 0 -0.3255687 -0.9455184 0 -0.3255687 0.9238787 0 0.3826853 0.9238787 0 0.3826853 -5.51887e-7 -0.8829477 0.4694713 -7.77154e-7 -0.8829492 0.4694685 4.84487e-6 -0.8829516 0.4694638 -8.54003e-7 -0.8829482 0.4694705 2.27477e-6 -0.8829467 0.4694731 5.51888e-7 -0.8829477 0.4694713 -2.27477e-6 -0.8829467 0.4694731 -2.5246e-6 -0.8829458 0.4694751 -1.20641e-6 -0.8829494 0.4694682 -4.84486e-6 -0.8829517 0.4694638 1.2064e-6 -0.8829494 0.4694682 -2.57581e-6 -0.8829465 0.4694737 4.59653e-6 -0.8829446 0.4694771 8.54002e-7 -0.8829482 0.4694705 -4.59654e-6 -0.8829446 0.4694771 2.18294e-6 -0.8829483 0.4694703 -3.99693e-6 -0.8829498 0.4694674 2.52461e-6 -0.8829457 0.469475 3.99693e-6 -0.8829498 0.4694674 -9.44649e-6 -0.8829456 0.4694753 -5.38526e-6 -0.8829499 0.4694674 2.5758e-6 -0.8829465 0.4694737 5.38525e-6 -0.8829498 0.4694674 1.0262e-5 -0.8829513 0.4694644 7.23963e-6 -0.8829466 0.4694734 -2.18294e-6 -0.8829483 0.4694703 -7.23966e-6 -0.8829466 0.4694733 -7.37333e-7 -0.8829464 0.469474 1.42634e-6 -0.8829462 0.4694742 9.44648e-6 -0.8829456 0.4694753 -1.42635e-6 -0.8829461 0.4694742 -4.32847e-6 -0.8829454 0.4694756 5.78689e-6 -0.8829498 0.4694676 -6.80679e-6 -0.8829499 0.4694671 1.01603e-6 -0.8829463 0.4694741 -1.0262e-5 -0.8829513 0.4694645 -1.01603e-6 -0.8829463 0.4694741 6.80677e-6 -0.88295 0.4694672 -7.12449e-7 -0.8829478 0.4694713 7.37335e-7 -0.8829463 0.4694738 7.12449e-7 -0.8829478 0.4694713 -3.91635e-6 -0.8829474 0.4694721 7.94712e-6 -0.8829458 0.4694749 4.32848e-6 -0.8829455 0.4694757 -7.94712e-6 -0.8829458 0.4694749 -2.06368e-6 -0.8829464 0.4694738 -6.86374e-6 -0.8829495 0.4694678 -5.78689e-6 -0.8829498 0.4694676 6.86377e-6 -0.8829495 0.4694679 -1.51106e-6 -0.8829462 0.4694741 -7.20038e-7 -0.882947 0.4694727 3.91635e-6 -0.8829474 0.4694721 7.20038e-7 -0.882947 0.4694727 -1.17175e-5 -0.8829472 0.4694722 -1.24263e-5 -0.8829488 0.4694693 2.06368e-6 -0.8829464 0.4694738 1.24263e-5 -0.8829488 0.4694693 2.54107e-6 -0.8829479 0.4694708 1.23303e-5 -0.8829472 0.4694724 1.51106e-6 -0.8829462 0.4694741 -1.23303e-5 -0.8829472 0.4694725 -2.06582e-6 -0.8829473 0.4694721 -9.79679e-7 -0.8829476 0.4694717 7.04339e-7 -0.8829475 0.4694716 1.00752e-6 -0.8829474 0.4694719 1.17176e-5 -0.8829473 0.4694723 -1.32316e-6 -0.8829475 0.4694718 3.67792e-7 -0.8829433 0.4694796 -1.00752e-6 -0.8829474 0.469472 -7.04339e-7 -0.8829475 0.4694716 -7.70648e-6 -0.8829488 0.4694693 -2.54106e-6 -0.8829479 0.4694708 -1.58732e-6 -0.882947 0.4694727 -3.67792e-7 -0.8829433 0.4694796 -1.93517e-6 -0.8829523 0.4694628 5.07317e-6 -0.8829478 0.4694711 7.70648e-6 -0.8829488 0.4694693 -4.31348e-6 -0.8829479 0.4694709 -7.51905e-7 -0.8829485 0.4694697 2.06582e-6 -0.8829473 0.4694721 1.93517e-6 -0.8829523 0.4694628 2.24029e-7 -0.882949 0.4694689 5.58432e-7 -0.8829469 0.469473 1.58732e-6 -0.8829471 0.4694727 7.51905e-7 -0.8829485 0.4694697 -3.05139e-6 -0.8829464 0.4694739 -1.22096e-5 -0.8829482 0.4694704 9.79679e-7 -0.8829476 0.4694717 -5.07315e-6 -0.8829478 0.4694712 -5.58432e-7 -0.8829469 0.469473 2.12559e-7 -0.8829472 0.4694723 -1.11324e-5 -0.8829427 0.4694808 1.22096e-5 -0.8829482 0.4694704 6.19345e-6 -0.882948 0.4694709 8.61054e-6 -0.8829463 0.469474 4.31348e-6 -0.8829479 0.4694709 1.11324e-5 -0.8829427 0.4694808 -4.12458e-7 -0.8829479 0.4694709 -8.28335e-6 -0.8829446 0.4694772 -2.1256e-7 -0.8829472 0.4694723 -8.11222e-6 -0.8829532 0.4694609 -4.36834e-7 -0.8829482 0.4694705 5.0811e-7 -0.8829479 0.4694709 9.30378e-6 -0.8829519 0.4694635 -8.61054e-6 -0.8829463 0.469474 3.05139e-6 -0.8829464 0.4694739 -9.30375e-6 -0.8829519 0.4694635 -5.08111e-7 -0.8829479 0.4694709 8.11222e-6 -0.8829532 0.4694609 8.28332e-6 -0.8829446 0.4694772 -4.18548e-7 -0.8829476 0.4694716 -1.60603e-6 -0.8829443 0.4694777 -6.19345e-6 -0.882948 0.4694709 1.60603e-6 -0.8829444 0.4694777 4.36832e-7 -0.8829482 0.4694705 4.12458e-7 -0.8829479 0.4694709 -9.0854e-7 -0.8829453 0.469476 9.0854e-7 -0.8829452 0.469476 -1.35293e-6 -0.8829469 0.4694729 -2.24029e-7 -0.882949 0.4694689 7.77153e-7 -0.8829492 0.4694685 0 -0.8829571 0.4694536 1.35293e-6 -0.8829469 0.4694728 4.18549e-7 -0.8829476 0.4694717 1.32316e-6 -0.8829475 0.4694718 0 -0.8829571 0.4694537 0.9781477 0 0.2079113 0.9781477 0 0.2079113 0.9455184 0 -0.3255687 0.9455184 0 -0.3255687 -0.7902586 -0.004729926 -0.6127552 -0.8182837 0 -0.5748144 -0.7262994 -0.005156278 -0.6873593 -0.757921 0 -0.6523466 -0.6553094 -0.005622804 -0.7553396 -0.6902436 0 -0.723577 -0.5779551 -0.006126224 -0.8160455 -0.6159124 0 -0.7878146 -0.4949774 -0.006645381 -0.8688804 -0.5355936 0 -0.8444759 -0.4071485 -0.007174074 -0.9133338 -0.4501204 0 -0.8929678 -0.3152529 -0.00769633 -0.9489765 -0.3603263 0 -0.9328263 -0.2202926 -0.008152484 -0.9753997 -0.2670451 0 -0.963684 -0.1469099 -0.004309058 -0.9891405 -0.1711732 0 -0.9852409 -0.04913276 -0.004393875 -0.9987826 -0.07368707 0 -0.9972814 0.02454972 0 -0.9996986 0.04913276 -0.004393875 -0.9987826 0.1225608 0 -0.992461 0.1469099 -0.004309058 -0.9891405 0.2432816 0 -0.9699558 0.2202925 -0.008152306 -0.9753997 0.3372877 0 -0.9414016 0.3152556 -0.007695853 -0.9489756 0.4280606 0 -0.90375 0.4071468 -0.007174372 -0.9133345 0.5146884 0 -0.8573774 0.4949774 -0.006645381 -0.8688804 0.5963531 0 -0.8027223 0.5779572 -0.006125569 -0.8160441 0.6722461 0 -0.7403278 0.6553094 -0.005622804 -0.7553396 0.7416554 0 -0.6707811 0.7262994 -0.005156278 -0.6873593 0.8039098 0 -0.5947513 0.7902586 -0.004729926 -0.6127552 0.8182837 0 -0.5748144 0.757921 0 -0.6523466 0.6902436 0 -0.723577 0.6159102 0 -0.7878164 0.5355936 0 -0.8444759 0.4501204 0 -0.8929678 0.3603263 0 -0.9328263 0.2670439 0 -0.9636843 0.1711732 0 -0.9852409 0.07368707 0 -0.9972814 -0.02454972 0 -0.9996986 -0.1225608 0 -0.992461 -0.2432821 0 -0.9699555 -0.3372862 0 -0.9414022 -0.4280615 0 -0.9037495 -0.5146884 0 -0.8573774 -0.5963531 0 -0.8027223 -0.6722461 0 -0.7403278 -0.7416554 0 -0.6707811 -0.8039098 0 -0.5947513 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 -0.9781477 0 0.2079111 -0.9781477 0 0.2079111 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0.7336196 0 0.6795603 0.6644383 0 0.7473431 0.5890219 0 0.8081172 0.5080675 0 0.8613172 0.4223499 0 0.9064329 0.3326886 0 0.9430368 0.23989 0 0.9708001 0.1448305 0 0.9894565 0.04843008 0 0.9988266 -0.0484302 0 0.9988266 -0.1448302 0 0.9894565 -0.2398895 0 0.9708002 -0.3326893 0 0.9430364 -0.4223499 0 0.9064329 -0.5080675 0 0.8613172 -0.5890219 0 0.8081172 -0.6644396 0 0.747342 -0.7336183 0 0.6795616 -0.7336183 0 0.6795616 -0.6644396 0 0.747342 -0.5890219 0 0.8081172 -0.5080675 0 0.8613172 -0.4223499 0 0.9064329 -0.3326893 0 0.9430364 -0.2398895 0 0.9708002 -0.1448302 0 0.9894565 -0.0484302 0 0.9988266 0.04843008 0 0.9988266 0.1448305 0 0.9894565 0.23989 0 0.9708001 0.3326886 0 0.9430368 0.4223499 0 0.9064329 0.5080675 0 0.8613172 0.5890219 0 0.8081172 0.6644383 0 0.7473431 0.7336196 0 0.6795603 0.9781477 0 0.2079114 0.9781477 0 0.2079114 -0.9462101 0 -0.3235529 -0.9094704 0 -0.4157686 -0.8637711 0 -0.5038844 -0.8095608 0 -0.587036 -0.7473733 0 -0.6644045 -0.6778097 0 -0.7352374 -0.6015822 0 -0.7988108 -0.5194382 0 -0.8545081 -0.4321497 0 -0.9018019 -0.3406018 0 -0.9402076 -0.245716 0 -0.9693419 -0.1484089 0 -0.9889261 -0.04963892 0 -0.9987672 0.0496388 0 -0.9987672 0.1484093 0 -0.9889261 0.2457154 0 -0.9693421 0.3406026 0 -0.9402074 0.4321497 0 -0.9018019 0.519437 0 -0.8545086 0.6015835 0 -0.79881 0.6778109 0 -0.7352362 0.747372 0 -0.6644058 0.8095608 0 -0.587036 0.8637701 0 -0.5038862 0.9094704 0 -0.4157686 0.9462101 0 -0.3235529 0.9462101 0 -0.3235529 0.9094704 0 -0.4157686 0.8637701 0 -0.5038862 0.8095608 0 -0.587036 0.747372 0 -0.6644058 0.6778109 0 -0.7352362 0.6015835 0 -0.79881 0.519437 0 -0.8545086 0.4321497 0 -0.9018019 0.3406026 0 -0.9402074 0.2457154 0 -0.9693421 0.1484093 0 -0.9889261 0.0496388 0 -0.9987672 -0.04963892 0 -0.9987672 -0.1484089 0 -0.9889261 -0.245716 0 -0.9693419 -0.3406018 0 -0.9402076 -0.4321497 0 -0.9018019 -0.5194382 0 -0.8545081 -0.6015822 0 -0.7988108 -0.6778097 0 -0.7352374 -0.7473733 0 -0.6644045 -0.8095608 0 -0.587036 -0.8637711 0 -0.5038844 -0.9094704 0 -0.4157686 -0.9462101 0 -0.3235529 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 -0.1391721 0 0.9902682 -0.1391721 0 0.9902682 0 1 0 0 1 0 0 1 0 0 1 0 -0.9986296 0 0.05233597 -0.9986296 0 0.05233597 -0.20791 0 -0.978148 -0.20791 0 -0.978148 0.1391757 0 -0.9902677 0.1391757 0 -0.9902677 0.6018114 0 -0.7986382 0.6018114 0 -0.7986382 0.9455186 0 0.3255681 0.9455186 0 0.3255681 -0.08913487 0.003509402 0.9960134 -0.1250764 -4.65054e-5 0.992147 0 0 1 0.08019238 0 0.9967795 0.08913487 0.003509342 0.9960134 -0.9998893 0.002117693 -0.01472949 -0.9983048 0 -0.05820286 -0.9972254 0.002230703 0.07440751 -0.9995189 0 0.0310167 -0.9866313 0.002355456 0.1629509 -0.9927741 0 0.119998 -0.9681881 0.002494513 0.2502115 -0.9781244 0 0.2080209 -0.9420407 0.00264883 0.3354883 -0.9556885 0 0.2943799 -0.9084042 0.002816319 0.4180835 -0.9256392 0 0.3784074 -0.8675252 0.00300157 0.4973842 -0.8882189 0 0.4594206 -0.819741 0.003204286 0.5727254 -0.8437382 0 0.536755 -0.7654138 0.003421306 0.6435294 -0.7925215 0 0.609844 -0.7049906 0.003652334 0.7092072 -0.7349988 0 0.6780684 -0.6389169 0.003900289 0.7692658 -0.6716442 0 0.7408738 -0.5677399 0.004151165 0.8231976 -0.6029089 0 0.79781 -0.4920145 0.004408359 0.8705759 -0.5294085 0 0.8483671 -0.4123245 0.004656791 0.9110251 -0.4516568 0 0.8921917 -0.3293482 0.004886925 0.9441959 -0.3703197 0 0.9289044 -0.2436498 0.005096375 0.9698498 -0.2860242 0 0.9582225 -0.1415118 0.01622927 0.9898035 -0.1781101 0 0.9840105 -0.1781102 0 0.9840106 -0.1556186 3.91332e-4 0.9878172 -0.2085331 0.09596687 0.9732956 -0.145569 -0.0188986 0.9891676 -0.08016973 0.2148625 0.9733483 -0.1086407 -0.04403042 0.9931055 -0.06688666 0 0.9977605 0 0.7147741 0.6993554 0.0223298 0 0.9997507 -0.0223298 0 0.9997507 0.06688666 0 0.9977605 0.08016973 0.2148625 0.9733483 0.1266512 3.9276e-4 0.9919473 0.1455686 -0.01889818 0.9891677 0.1556187 3.92844e-4 0.9878171 0.1781098 0 0.9840106 0.1775822 -4.63174e-5 0.984106 0.1415466 0.01621377 0.9897988 0.1781098 0 0.9840106 0.2645844 0 0.9643625 0.2436488 0.005096495 0.9698501 0.3495196 0 0.9369291 0.3293482 0.004886925 0.9441959 0.4316371 0 0.9020473 0.4123261 0.004656612 0.9110245 0.510339 0 0.8599733 0.4920145 0.00440818 0.8705759 0.5849584 0 0.8110633 0.56774 0.004151403 0.8231974 0.6549373 0 0.7556833 0.638919 0.003899812 0.7692642 0.719692 0 0.6942936 0.7049907 0.003652572 0.7092071 0.778715 0 0.6273779 0.7654098 0.003422081 0.6435342 0.8315491 0 0.5554515 0.8197391 0.003204762 0.5727282 0.877748 0 0.4791228 0.8675252 0.00300157 0.4973842 0.9169671 0 0.398963 0.9084028 0.002816796 0.4180869 0.9488806 0 0.3156353 0.9420407 0.002649068 0.3354882 0.9732385 0 0.2297972 0.968188 0.002494275 0.2502116 0.9898492 0 0.1421217 0.9866313 0.002355217 0.1629511 0.9985778 0 0.05331271 0.9972257 0.002230525 0.07440334 0.999355 0 -0.03591245 0.9998892 0.002117276 -0.01473355 0.998305 0 -0.05819857 0.9995189 0 0.0310167 0.9927736 0 0.1200023 0.9781236 0 0.208025 0.9556897 0 0.294376 0.9256407 0 0.3784037 0.8882189 0 0.4594206 0.8437401 0 0.5367519 0.7925236 0 0.6098414 0.735001 0 0.6780661 0.671642 0 0.7408758 0.6029109 0 0.7978084 0.5294066 0 0.8483682 0.4516568 0 0.8921917 0.3703197 0 0.9289044 0.2860242 0 0.9582225 0.2085332 0.0959689 0.9732953 0.1086407 -0.04403042 0.9931055 -0.1266506 3.9153e-4 0.9919473 -0.1775822 -4.64877e-5 0.984106 -0.264585 0 0.9643624 -0.3495196 0 0.9369291 -0.4316363 0 0.9020478 -0.51034 0 0.8599727 -0.5849574 0 0.811064 -0.6549373 0 0.7556833 -0.7196909 0 0.6942946 -0.778716 0 0.6273766 -0.8315491 0 0.5554515 -0.877748 0 0.4791228 -0.9169671 0 0.398963 -0.94888 0 0.3156373 -0.973239 0 0.2297951 -0.9898494 0 0.1421196 -0.9985777 0 0.05331486 -0.999355 0 -0.03591245 0.1250739 -4.63854e-5 0.9921475 0 0 1 -0.0801922 0 0.9967795 -1 0 0 -1 0 0 1 0 0 1 0 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0.7070996 0.7071139 7.09688e-6 0.7072339 0.7069795 0 0.7071068 0.7071068 0 0.7045151 0.7045151 0.08553928 0.6635748 0.7045132 0.2516536 0.584075 0.7045073 0.4031451 0.4706113 0.7045056 0.5312224 0.3298317 0.7045227 0.6283779 0.1698466 0.7045023 0.689078 0 0.7045321 0.7096722 -0.169803 0.7045325 0.6890578 -0.3298195 0.7045037 0.6284056 -0.4705905 0.70452 0.5312215 -0.5840738 0.704508 0.4031453 -0.6635733 0.7045102 0.251666 -0.7045117 0.7045179 0.08554446 -0.7045146 0.7045146 0.08554899 -0.6635685 0.70452 0.2516512 -0.584075 0.7045073 0.4031451 -0.4706132 0.7045056 0.5312203 -0.3298306 0.704521 0.6283806 -0.1698466 0.7045023 0.689078 0 0.7045321 0.7096721 0.169803 0.7045325 0.6890578 0.3298195 0.7045037 0.6284056 0.4705839 0.7045228 0.5312237 0.5840738 0.704508 0.4031453 0.6635765 0.7045098 0.2516589 0.7045188 0.7045107 0.08554536 -0.7071068 0.7071068 0 -0.7071068 0.7071068 0 -0.7071068 0.7071068 0 0.9927087 0 0.1205384 0.9350175 0 0.3546018 0.8229923 0 0.5680526 0.6631143 0 0.7485182 0.4647307 0 0.8854522 0.2393211 0 0.9709405 0 0 1 -0.2393211 0 0.9709405 -0.4647307 0 0.8854522 -0.6631172 0 0.7485156 -0.8229923 0 0.5680526 -0.9350135 0 0.3546122 -0.9927087 0 0.1205384 -0.9927087 0 0.1205384 -0.9350135 0 0.3546122 -0.8229923 0 0.5680526 -0.6631172 0 0.7485156 -0.4647307 0 0.8854522 -0.2393211 0 0.9709405 0 0 1 0.2393211 0 0.9709405 0.4647307 0 0.8854522 0.6631143 0 0.7485182 0.8229923 0 0.5680526 0.9350175 0 0.3546018 0.9927087 0 0.1205384 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 -0.7071068 -0.7071068 0 -0.7071068 -0.7071068 0 -0.7071067 -0.7071067 0 -0.7045148 -0.7045148 0.08554345 -0.6635745 -0.7045081 0.2516689 -0.5840686 -0.7045068 0.4031553 -0.4706031 -0.7045211 0.5312088 -0.329798 -0.7045075 0.6284126 -0.1698474 -0.704532 0.6890476 0 -0.7045257 0.7096784 0.1698415 -0.7045237 0.6890575 0.3298072 -0.7045304 0.6283823 0.4706229 -0.7045068 0.5312102 0.5840623 -0.7045227 0.4031363 0.6635725 -0.7045141 0.2516574 0.7045161 -0.7045135 0.085545 0.704519 -0.70451 0.08554869 0.6635758 -0.7045083 0.2516646 0.5840656 -0.7045105 0.4031532 0.4705991 -0.7045239 0.5312086 0.3297972 -0.7045054 0.6284157 0.1698474 -0.704532 0.6890476 0 -0.7045257 0.7096784 -0.1698415 -0.7045237 0.6890575 -0.3298072 -0.7045304 0.6283823 -0.4706184 -0.70451 0.5312099 -0.5840654 -0.704519 0.4031385 -0.6635733 -0.7045103 0.251666 -0.7045161 -0.7045135 0.085545 0.7071113 -0.7071023 0 0.7071115 -0.707102 -2.53585e-7 0.7071068 -0.7071068 0 + + + + + + + + + + + + + + + 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 +

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

+
+
+
+
+ + + + + -4.37114e-11 0 0.001 -0.675 0 0.001 0 0 -0.001 0 -4.37114e-11 0.26 0 0 0 1 + + + + + + + + + + + + + +
diff --git a/kuka_kr16_support/meshes/kr16_2/visual/link_3.dae b/kuka_kr16_support/meshes/kr16_2/visual/link_3.dae new file mode 100644 index 000000000..f82e0bd44 --- /dev/null +++ b/kuka_kr16_support/meshes/kr16_2/visual/link_3.dae @@ -0,0 +1,395 @@ + + + + + Blender User + Blender 2.79.0 commit date:2017-09-11, commit time:10:43, hash:5bd8ac9abfa + + 2017-11-10T20:34:37 + 2017-11-10T20:34:37 + + 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.512 0.2088141 0.07027201 1 + + + 0.015625 0.015625 0.015625 1 + + + 1 + + + 1 + + + + + + + + + + + 0 0 0 1 + + + 0 0 0 1 + + + 0.00200704 0.00200704 0.00200704 1 + + + 0.03125 0.03125 0.03125 1 + + + 10 + + + 1 + + + + + + + + + + + + + + + + + + + 283.2743 12.96539 1454 287.7838 10.82781 1454 290.0865 12.08531 1454 285.1817 11.16394 1454 289.9148 18.08637 1454 287.544 19.21018 1454 284.9654 18.72583 1454 283.164 16.81828 1454 291.1722 15.78396 1454 290.9945 13.70213 1454 282.8 15 1454 290.9945 16.29787 1470 290.0865 17.91469 1470 287.7838 19.1722 1470 285.1817 18.83606 1470 283.2743 17.03461 1470 282.8 15 1470 283.164 13.18173 1470 284.9654 11.27417 1470 287.544 10.78982 1470 289.9148 11.91363 1470 291.1722 14.21604 1470 285.1817 -11.16394 1470 287.7838 -10.82781 1470 278.0592 15.47967 1470 276.3073 11.25006 1470 274.5249 2.289041 1470 288.1184 -22.92145 1470 290.2676 -22.30224 1470 287.544 -19.21018 1470 290.0865 -12.08531 1470 298.8776 -6.827959 1470 275.1224 6.827959 1470 299.4751 2.289041 1470 298.8776 6.827959 1470 297.6927 11.25006 1470 285.8817 -22.92145 1470 292.1614 -21.11223 1470 289.9148 -18.08637 1470 288.1184 22.92145 1470 285.8817 22.92145 1470 283.7324 22.30224 1470 281.8386 21.11223 1470 290.9945 -13.70213 1470 297.6927 -11.25006 1470 299.4751 -2.289041 1470 295.9408 15.47967 1470 280.3482 -19.44445 1470 283.164 -16.81828 1470 284.9654 -18.72583 1470 293.6518 19.44445 1470 292.1614 21.11223 1470 290.2676 22.30224 1470 291.1722 -15.78396 1470 295.9408 -15.47967 1470 274.5249 -2.289041 1470 275.1224 -6.827959 1470 283.2743 -12.96539 1470 276.3073 -11.25006 1470 278.0592 -15.47967 1470 281.8386 -21.11223 1470 283.7324 -22.30224 1470 293.6518 -19.44445 1470 280.3482 19.44445 1470 282.8 -15 1470 281.3087 -20.70006 1449.887 283.3982 -22.17423 1449.395 285.4991 -22.88816 1448.85 287.7448 -22.9958 1448.213 289.9514 -22.46445 1447.52 291.8792 -21.37742 1446.878 293.3546 -19.89672 1446.352 277.9758 15.40918 1450.578 275.7281 9.596776 1450.971 274.5648 3.059078 1451.155 274.4627 -1.14958 1451.166 274.8993 -5.706508 1451.102 276.0329 -10.50442 1450.92 277.9746 -15.40693 1450.578 285.5004 22.88852 1448.848 283.4315 22.18785 1449.386 281.2658 20.62655 1449.894 293.3551 19.89598 1446.352 291.8787 21.37782 1446.879 289.9601 22.46084 1447.522 287.7669 22.9964 1448.217 295.8442 -15.75726 1445.412 298.5178 -8.666261 1444.299 299.5314 -2.239425 1443.854 299.4001 3.43368 1443.912 298.5174 8.667369 1444.3 295.844 15.75771 1445.412 291.1722 -14.21604 1454 289.9148 -11.91363 1454 287.544 -10.78982 1454 284.9654 -11.27417 1454 283.164 -13.18173 1454 282.8 -15 1454 283.2743 -17.03461 1454 285.1817 -18.83606 1454 287.7838 -19.1722 1454 290.0865 -17.91469 1454 290.9945 -16.29787 1454 244.1281 -37 1450.946 244.1281 23 1450.946 236.6565 23 1449.407 251.6975 -37 1451.895 251.6975 23 1451.895 259.3179 -37 1452.248 259.3179 23 1452.248 266.9425 -37 1452.002 266.9425 23 1452.002 310.1854 -37 1438.301 310.1854 23 1438.301 303.5017 23 1441.978 316.5603 -37 1434.111 316.5603 23 1434.111 322.5872 -37 1429.434 322.5872 23 1429.434 328.2289 -37 1424.299 328.2289 23 1424.299 333.4508 -37 1418.738 338.2208 -37 1412.785 336.6866 -35.3156 1414.808 334.134 -34.10517 1417.951 331.7588 -32.24032 1420.639 296.5503 23 1445.12 303.5017 -37 1441.978 296.5503 -37 1445.12 282.0169 -37 1449.725 289.374 -37 1447.708 274.5244 -37 1451.159 274.5244 23 1451.159 282.0169 23 1449.725 236.6565 -37 1449.407 230.0354 -23.61064 1447.525 233.39 -14.79412 1448.544 235.7486 -2.309759 1449.179 234.3761 11.25528 1448.818 231.677 19.51111 1448.034 230.2324 23 1447.582 229.3285 -37 1447.287 225.9714 -31.65618 1446.108 341.7423 -36.02652 1407.7 339.3706 -35.96292 1411.216 342.0852 -37.00658 1407.196 222.9407 -37 1444.912 331.7526 23 1420.644 333.7723 -33.85317 1420.644 336.2565 -35.15132 1420.644 338.9613 -35.88679 1420.644 341.7608 -36.02536 1420.644 344.525 -35.56061 1420.644 344.0603 -35.71215 1406.938 347.1253 -34.51414 1420.644 346.7117 -34.75754 1406.314 349.4409 -32.9346 1420.644 349.0003 -33.32104 1406.006 351.364 -30.89542 1420.644 351.4378 -30.87678 1406.008 353.0256 -28.06076 1406.374 352.8053 -28.49139 1420.644 353.8681 -25.12535 1406.977 353.6978 -25.83429 1420.644 354 -23.04765 1420.644 354 -5.443346 1410.306 354 1.174876 1410.462 354.0001 -14.78051 1409.285 354 25.05236 1420.644 354.0001 17.48921 1408.798 354 7.786807 1410.134 353.9104 26.84702 1406.436 336.9828 37.41609 1420.644 334.5 36.31068 1420.644 351.5172 32.69356 1420.644 349.6987 34.71324 1420.644 339.6412 37.98114 1420.644 345.0172 37.41609 1420.644 342.3589 37.98114 1420.644 347.5 36.31068 1420.644 353.7159 27.75521 1420.644 352.8761 30.33993 1420.644 332.3013 34.71324 1420.644 330.4828 32.69356 1420.644 329.1239 30.33993 1420.644 328.2841 27.75521 1420.644 327.9466 23.00241 1420.644 353.1336 29.8081 1405.736 351.8023 32.33456 1405.33 349.6844 34.78328 1405.169 347.1051 36.56022 1405.417 344.5784 37.57823 1405.951 341.8962 38.04848 1406.782 339.1734 37.95071 1407.876 336.5331 37.28952 1409.174 334.4925 36.30627 1410.354 332.1886 34.66332 1411.877 330.193 32.32654 1413.471 329.113 30.31517 1414.536 328.1369 27.30136 1415.83 328 22.99999 1416.987 299.9867 23.00219 1427.238 238.8703 23 1446.814 355.0033 -37 1334.217 353.4033 -37 1337.656 351.6788 -37 1330.1 356.3745 -37 1341.98 354.5062 -37 1345.327 357.1124 -37 1349.829 354.9802 -37 1353.062 357.2122 -37 1357.712 354.8222 -37 1360.81 347.2002 -37 1311.946 346.4151 -37 1315.536 342.9108 -37 1308.623 350.401 -37 1319.15 349.3442 -37 1322.711 356.6731 -37 1365.577 354.0331 -37 1368.52 355.4988 -37 1373.372 352.6182 -37 1376.14 308.0584 -37 1436.947 294.1053 -37 1443.667 301.219 -37 1440.592 165.7825 -37 1330.904 168.3212 -37 1330.1 166.5967 -37 1337.656 168.0438 -37 1323.352 170.6558 -37 1322.711 174.3603 -37 1308.92 177.0892 -37 1308.623 173.585 -37 1315.536 178.3741 -37 1302.134 181.1452 -37 1302.02 353.0077 -37 1326.59 320.7343 -37 1428.05 314.5779 -37 1432.758 286.7646 -37 1446.152 225.8947 -37 1443.667 233.2354 -37 1446.152 218.781 -37 1440.592 192.5064 -37 1425.015 193.5135 -37 1422.857 199.2657 -37 1428.05 187.0571 -37 1419.319 188.2038 -37 1417.212 182.0871 -37 1413.199 183.3719 -37 1411.153 177.6291 -37 1406.697 179.0498 -37 1404.72 164.1403 -37 1338.614 165.4938 -37 1345.327 170.9093 -37 1316.008 303.4769 -37 1268.01 304.6759 -37 1271.16 297.6935 -37 1267.798 310.38 -37 1271.817 311.3609 -37 1275.081 353.6969 -37 1381.047 350.5869 -37 1383.618 351.2793 -37 1388.551 347.9528 -37 1390.907 344.6645 -37 1402.849 340.9501 -37 1404.72 344.7334 -37 1397.956 331.7962 -37 1417.212 326.4865 -37 1422.857 218.3386 -37 1442.874 211.3579 -37 1439.211 211.9416 -37 1436.947 163.9166 -37 1370.018 165.967 -37 1368.52 167.3818 -37 1376.14 163.0159 -37 1362.186 165.1779 -37 1360.81 162.7525 -37 1354.307 165.0198 -37 1353.062 163.1281 -37 1346.433 182.9243 -37 1295.697 185.726 -37 1295.768 187.9809 -37 1289.649 190.8011 -37 1289.911 288.8608 -37 1262.131 290.4603 -37 1265.016 283.0244 -37 1262.832 296.2881 -37 1264.774 316.9521 -37 1276.171 317.7041 -37 1279.533 323.1499 -37 1281.043 323.6634 -37 1284.488 328.9327 -37 1286.401 329.199 -37 1289.911 334.2626 -37 1292.21 334.274 -37 1295.768 339.1044 -37 1298.431 338.8548 -37 1302.02 348.2619 -37 1395.834 336.6282 -37 1411.153 204.6968 -37 1434.994 205.4221 -37 1432.758 198.3992 -37 1430.252 173.7124 -37 1399.856 175.2666 -37 1397.956 170.3628 -37 1392.719 172.0472 -37 1390.907 167.6022 -37 1385.335 169.4131 -37 1383.618 165.4487 -37 1377.751 281.2438 -37 1260.099 275.4353 -37 1261.262 343.4265 -37 1305.024 263.8749 -37 1449.921 271.599 -37 1449.289 256.1251 -37 1449.921 193.5108 -37 1284.03 196.3366 -37 1284.488 199.4777 -37 1278.878 202.2959 -37 1279.533 212.5627 -37 1270.104 215.3242 -37 1271.16 208.6391 -37 1275.081 219.5949 -37 1266.541 222.3065 -37 1267.798 273.4873 -37 1258.69 267.7434 -37 1260.316 279.2458 -37 1448.03 248.401 -37 1449.289 240.7542 -37 1448.03 205.8422 -37 1274.226 234.4078 -37 1261.178 236.9756 -37 1262.832 229.5397 -37 1265.016 242.0912 -37 1259.413 244.5648 -37 1261.262 265.6421 -37 1257.914 260 -37 1260 226.8925 -37 1263.559 249.8923 -37 1258.277 252.2566 -37 1260.316 257.7599 -37 1257.776 252.2566 -107 1260.316 244.5648 -107 1261.262 236.9756 -107 1262.832 229.5397 -107 1265.016 222.3065 -107 1267.798 215.3242 -107 1271.16 208.6391 -107 1275.081 202.2959 -107 1279.533 196.3366 -107 1284.488 190.8011 -107 1289.911 185.726 -107 1295.768 181.1452 -107 1302.02 177.0892 -107 1308.623 173.585 -107 1315.536 170.6558 -107 1322.711 168.3212 -107 1330.1 166.5967 -107 1337.656 165.4938 -107 1345.327 165.0198 -107 1353.062 165.1779 -107 1360.81 165.967 -107 1368.52 167.3818 -107 1376.14 169.4131 -107 1383.618 172.0472 -107 1390.907 175.2666 -107 1397.956 179.0498 -107 1404.72 183.3719 -107 1411.153 188.2038 -107 1417.212 193.5135 -107 1422.857 199.2657 -107 1428.05 205.4221 -107 1432.758 211.9416 -107 1436.947 218.781 -107 1440.592 225.8947 -107 1443.667 233.2354 -107 1446.152 240.7542 -107 1448.03 248.401 -107 1449.289 256.1251 -107 1449.921 263.8749 -107 1449.921 271.599 -107 1449.289 279.2458 -107 1448.03 286.7646 -107 1446.152 296.5945 -107 1442.732 342.9108 -107 1308.623 338.8548 -107 1302.02 334.274 -107 1295.768 329.199 -107 1289.911 323.6634 -107 1284.488 317.7041 -107 1279.533 311.3609 -107 1275.081 304.6759 -107 1271.16 297.6935 -107 1267.798 290.4603 -107 1265.016 283.0244 -107 1262.832 275.4353 -107 1261.262 267.7434 -107 1260.316 260 -107 1260 296.5744 -88 1442.677 301.219 -88 1440.592 308.0584 -88 1436.947 314.5779 -88 1432.758 320.7343 -88 1428.05 326.4865 -88 1422.857 331.7962 -88 1417.212 336.6282 -88 1411.153 340.9501 -88 1404.72 344.7334 -88 1397.956 347.9528 -88 1390.907 350.5869 -88 1383.618 352.6182 -88 1376.14 354.0331 -88 1368.52 354.8222 -88 1360.81 354.9802 -88 1353.062 354.5062 -88 1345.327 353.4033 -88 1337.656 351.6788 -88 1330.1 349.3442 -88 1322.711 347.9084 -107 1318.842 347.8593 -88 1318.865 190.1356 -107 1393.974 193.8535 -107 1399.996 186.9644 -107 1387.647 184.3649 -107 1381.064 191.9279 -107 1312.974 188.48 -107 1319.155 239.0097 -107 1432.197 232.2691 -107 1430.04 202.8092 -107 1410.939 207.9769 -107 1415.775 198.089 -107 1405.666 185.5918 -107 1325.616 195.9085 -107 1307.122 200.3908 -107 1301.645 245.9145 -107 1433.75 182.3573 -107 1374.277 180.9574 -107 1367.34 180.1761 -107 1360.306 180.0196 -107 1353.23 225.7456 -107 1427.296 180.489 -107 1346.168 181.5806 -107 1339.176 183.286 -107 1332.307 263.5387 -107 1275.078 256.4613 -107 1275.078 290.845 -107 1428.873 280.9903 -107 1432.197 219.4902 -107 1423.985 213.5518 -107 1420.135 210.7161 -107 1291.983 216.4784 -107 1287.874 249.4117 -107 1275.704 277.5551 -107 1276.95 284.3845 -107 1278.807 274.0855 -107 1433.75 260 -107 1435 267.0704 -107 1434.687 205.3395 -107 1296.586 222.5812 -107 1284.291 228.977 -107 1281.26 242.4449 -107 1276.95 235.6155 -107 1278.807 270.5883 -107 1275.704 291.023 -107 1281.26 252.9296 -107 1434.687 297.4187 -107 1284.291 303.5216 -107 1287.874 331.52 -107 1319.155 309.2839 -107 1291.983 324.0915 -107 1307.122 319.6092 -107 1301.645 328.0721 -107 1312.974 334.001 -107 1324.605 314.6605 -107 1296.586 351.3352 -88 1317.425 351.3352 -109 1317.425 334.0102 -109 1324.603 290.8342 -109 1428.819 298.0142 -109 1446.153 298.0142 -88 1446.153 252.9296 -117 1434.687 260 -117 1435 245.9145 -117 1433.75 239.0097 -117 1432.197 232.2691 -117 1430.04 225.7456 -117 1427.296 219.4902 -117 1423.985 213.5518 -117 1420.135 207.9769 -117 1415.775 202.8092 -117 1410.939 198.089 -117 1405.666 193.8535 -117 1399.996 190.1356 -117 1393.974 186.9644 -117 1387.647 184.3649 -117 1381.064 182.3573 -117 1374.277 180.9574 -117 1367.34 180.1761 -117 1360.306 180.0196 -117 1353.23 180.489 -117 1346.168 181.5806 -117 1339.176 183.286 -117 1332.307 185.5918 -117 1325.616 188.48 -117 1319.155 191.9279 -117 1312.974 195.9085 -117 1307.122 200.3908 -117 1301.645 205.3395 -117 1296.586 210.7161 -117 1291.983 216.4784 -117 1287.874 222.5812 -117 1284.291 228.977 -117 1281.26 235.6155 -117 1278.807 242.4449 -117 1276.95 249.4117 -117 1275.704 257.716 -117 1275.004 263.5387 -117 1275.078 270.5883 -117 1275.704 277.5551 -117 1276.95 284.3845 -117 1278.807 291.023 -117 1281.26 297.4187 -117 1284.291 303.5216 -117 1287.874 309.2839 -117 1291.983 314.6605 -117 1296.586 319.6092 -117 1301.645 324.0915 -117 1307.122 328.0721 -117 1312.974 331.52 -117 1319.155 280.9903 -117 1432.197 287.7309 -117 1430.04 274.0855 -117 1433.75 267.0704 -117 1434.687 334.4082 -117 1325.616 336.714 -109 1332.307 336.714 -117 1332.307 338.4194 -109 1339.176 338.4194 -117 1339.176 339.5111 -109 1346.168 339.5111 -117 1346.168 339.9804 -109 1353.23 339.9804 -117 1353.23 339.8239 -109 1360.306 339.8239 -117 1360.306 339.0426 -109 1367.34 339.0426 -117 1367.34 337.6427 -109 1374.277 337.6427 -117 1374.277 335.6351 -109 1381.064 335.6351 -117 1381.064 333.0356 -109 1387.647 333.0356 -117 1387.647 329.8645 -109 1393.974 329.8645 -117 1393.974 326.1466 -109 1399.996 326.1466 -117 1399.996 321.911 -109 1405.666 321.911 -117 1405.666 317.1908 -109 1410.939 317.1908 -117 1410.939 312.0231 -109 1415.775 312.0231 -117 1415.775 306.4483 -109 1420.135 306.4483 -117 1420.135 300.5098 -109 1423.985 300.5098 -117 1423.985 294.2544 -109 1427.296 294.2544 -117 1427.296 324.0674 -88 1430.162 324.0674 -109 1430.162 329.7079 -109 1424.963 318.0404 -88 1434.908 318.0404 -109 1434.908 311.6632 -88 1439.172 311.6632 -109 1439.172 304.9744 -88 1442.928 304.9744 -109 1442.928 329.7079 -88 1424.963 341.996 -109 1423.743 341.996 -88 1423.743 353.7651 -88 1323.982 353.7651 -109 1323.982 355.725 -88 1330.695 355.725 -109 1330.695 357.2049 -88 1337.53 357.2049 -109 1337.53 358.1975 -88 1344.453 358.1975 -109 1344.453 363.1717 -88 1383.365 364.9359 -88 1375.915 366.1629 -88 1368.358 366.8463 -88 1360.733 366.9827 -88 1353.078 360.8793 -88 1390.67 346.7016 -88 1417.704 354.7595 -88 1404.695 358.0705 -88 1397.792 350.9635 -88 1411.344 364.9359 -109 1375.915 363.1717 -109 1383.365 366.1629 -109 1368.358 360.8793 -109 1390.67 358.0705 -109 1397.792 354.7595 -109 1404.695 350.9635 -109 1411.344 346.7016 -109 1417.704 366.9827 -109 1353.078 366.8463 -109 1360.733 346.7016 -77 1417.704 350.9635 -77 1411.344 354.7595 -77 1404.695 358.0705 -77 1397.792 360.8793 -77 1390.67 363.1717 -77 1383.365 364.9359 -77 1375.915 366.1629 -77 1368.358 366.8463 -77 1360.733 366.9827 -77 1353.078 341.996 -77 1423.743 346.7016 -117 1417.704 341.996 -117 1423.743 350.9635 -117 1411.344 354.7595 -117 1404.695 358.0705 -117 1397.792 360.8793 -117 1390.67 363.1717 -117 1383.365 364.9359 -117 1375.915 366.1629 -117 1368.358 366.8463 -117 1360.733 366.9827 -117 1353.078 354.9823 -82.17298 1436.067 357.181 -82.01925 1438.154 352.851 -82.93373 1434.045 371.4263 -77 1451.672 359.3572 -82.47885 1440.219 350.8745 -84.27033 1432.169 346.6311 -91.08467 1428.142 347.6995 -88.43098 1429.156 371.4263 -117 1451.672 357.181 -111.9808 1438.154 349.1335 -107.8719 1430.517 347.6995 -105.569 1429.156 354.9823 -111.827 1436.067 361.4217 -110.4671 1442.178 359.3572 -111.5212 1440.219 363.29 -85.13837 1443.951 364.8857 -87.22943 1445.465 361.4217 -83.53293 1442.178 349.1335 -86.12812 1430.517 352.851 -111.0663 1434.045 363.29 -108.8616 1443.951 366.1434 -89.72048 1446.658 345.972 -100.0195 1427.517 345.7493 -97 1427.305 350.8745 -109.7297 1432.169 367.0115 -101.4905 1447.482 366.1434 -104.2795 1446.658 367.0115 -92.50955 1447.482 367.552 -97.00003 1447.995 345.972 -93.98052 1427.517 346.6311 -102.9153 1428.142 364.8857 -106.7706 1445.465 382.7633 -117 1436.897 382.7633 -77 1436.897 379.5042 -77 1433.345 376.696 -77 1429.426 407.4285 -77 1349.895 397.8415 -77 1370.202 381.6988 -77 1380.426 375.9174 -77 1388.12 371.078 -77 1401.674 372.141 -77 1396.972 370.5884 -77 1406.47 370.6792 -77 1411.29 402.4963 -77 1368.948 385.2409 -77 1377.156 378.5759 -77 1384.098 373.762 -77 1392.432 371.3493 -77 1416.064 374.3796 -77 1425.199 393.3713 -77 1372.006 372.5887 -77 1420.723 389.1506 -77 1374.336 407.2682 -77 1368.263 376.696 -117 1429.426 374.3796 -117 1425.199 372.5887 -117 1420.723 371.3493 -117 1416.064 370.6792 -117 1411.29 371.078 -117 1401.674 372.141 -117 1396.972 407.4285 -117 1349.895 402.4963 -117 1368.948 397.8415 -117 1370.202 370.5884 -117 1406.47 373.762 -117 1392.432 378.5759 -117 1384.098 375.9174 -117 1388.12 381.6988 -117 1380.426 385.2409 -117 1377.156 407.2682 -117 1368.263 389.1506 -117 1374.336 393.3713 -117 1372.006 379.5042 -117 1433.345 386.7139 -111.9808 1351.525 389.7358 -111.827 1351.287 389.7358 -82.17298 1351.287 386.7139 -82.01925 1351.525 383.7231 -111.5212 1351.76 376.125 -106.7706 1352.358 376.125 -87.22943 1352.358 374.3966 -89.72048 1352.494 392.6649 -82.93373 1351.057 380.8858 -110.4671 1351.984 374.3966 -104.2795 1352.494 383.7231 -82.47885 1351.76 380.8858 -83.53293 1351.984 378.3181 -108.8616 1352.186 373.2034 -101.4905 1352.588 378.3181 -85.13837 1352.186 397.774 -107.8719 1350.655 399.7448 -105.569 1350.5 392.6649 -111.0663 1351.057 395.3813 -109.7297 1350.843 397.774 -86.12812 1350.655 395.3813 -84.27033 1350.843 401.2132 -102.9153 1350.384 372.5337 -95.89753 1352.641 373.2034 -92.50955 1352.588 401.2132 -91.08467 1350.384 399.7448 -88.43098 1350.5 402.119 -100.0195 1350.313 402.4251 -97 1350.289 372.5943 -98.51753 1352.636 402.119 -93.98052 1350.313 337.3676 -100.0195 1436.584 337.1449 -97 1436.372 338.0267 -102.9153 1437.209 339.0951 -105.569 1438.223 340.5291 -107.8719 1439.584 342.27 -109.7297 1441.236 344.2466 -111.0663 1443.112 346.3779 -111.827 1445.134 348.5766 -111.9808 1447.221 350.7528 -111.5212 1449.286 352.8172 -110.4671 1451.245 354.6856 -108.8616 1453.018 356.2813 -106.7706 1454.532 357.5389 -104.2795 1455.726 358.4071 -101.4905 1456.55 358.8945 -98.10183 1457.012 358.8503 -95.48249 1456.97 358.4071 -92.50955 1456.55 357.5389 -89.72048 1455.726 356.2813 -87.22943 1454.532 354.6856 -85.13837 1453.018 352.8172 -83.53293 1451.245 350.7528 -82.47885 1449.286 348.5766 -82.01925 1447.221 346.3779 -82.17298 1445.134 344.2466 -82.93373 1443.112 342.27 -84.27033 1441.236 340.5291 -86.12812 1439.584 339.0951 -88.43098 1438.223 338.0267 -91.08467 1437.209 337.3676 -93.98052 1436.584 401.1383 -100.0195 1337.851 401.4443 -97 1337.827 400.2325 -102.9153 1337.922 398.7641 -105.569 1338.038 396.7933 -107.8719 1338.193 394.4006 -109.7297 1338.381 391.6841 -111.0663 1338.595 388.755 -111.827 1338.826 385.7332 -111.9808 1339.064 382.7424 -111.5212 1339.299 379.905 -110.4671 1339.522 377.3373 -108.8616 1339.724 375.1443 -106.7706 1339.897 373.4158 -104.2795 1340.033 372.2226 -101.4905 1340.127 371.48 -97 1340.186 372.2226 -92.50955 1340.127 373.4158 -89.72048 1340.033 375.1443 -87.22943 1339.897 377.3373 -85.13837 1339.724 379.905 -83.53293 1339.522 382.7424 -82.47885 1339.299 385.7332 -82.01925 1339.064 388.755 -82.17298 1338.826 391.6841 -82.93373 1338.595 394.4006 -84.27033 1338.381 396.7933 -86.12812 1338.193 398.7641 -88.43098 1338.038 400.2325 -91.08467 1337.922 401.1383 -93.98052 1337.851 238.8006 38.64306 1442.965 140.175 38.02933 1452.134 140.485 29.58671 1454.27 238.8431 31.01103 1445.101 238.8211 43.30015 1441.405 139.0666 43.11292 1450.606 139.5243 -38.53163 1452.023 221.9346 -38.69491 1444.492 140.2262 -32.55788 1453.593 140.955 -22.02801 1455.707 143.3196 -19.90442 1455.793 145.6279 -16.15769 1456.078 148.7653 -7.499527 1456.552 147.3532 -12.25604 1456.344 149.5439 1.531442 1456.712 149.4105 -3.313764 1456.674 147.9164 10.67178 1456.438 149.087 5.784677 1456.62 146.4107 14.52986 1456.203 143.7433 19.38818 1455.834 141.886 21.37153 1455.694 139.3896 22.68071 1455.628 145.9408 -15.47967 1470 143.6518 -19.44445 1470 147.6927 -11.25006 1470 148.8776 -6.827959 1470 149.4751 -2.289041 1470 149.4751 2.289041 1470 148.8776 6.827959 1470 147.6927 11.25006 1470 145.9408 15.47967 1470 143.6518 19.44445 1470 131.8385 -21.11223 1470 130.3482 -19.44445 1470 130.0762 -19.10255 1456.172 131.6103 -20.94111 1455.894 133.7324 -22.30224 1470 133.374 -22.16429 1455.702 135.8816 -22.92145 1470 135.9002 -22.97982 1455.564 138.1183 -22.92145 1470 138.7167 -22.83467 1455.585 142.1614 -21.11223 1470 140.2676 -22.30224 1470 142.1614 21.11223 1470 140.2676 22.30224 1470 138.1183 22.92145 1470 135.8816 22.92145 1470 135.8985 22.97973 1455.566 133.373 22.16388 1455.702 133.7324 22.30224 1470 131.5323 20.88049 1455.906 131.8385 21.11223 1470 130.1555 19.20052 1456.156 130.3482 19.44445 1470 128.0592 15.47967 1470 126.3073 11.25006 1470 127.8596 15.114 1456.674 125.1224 6.827959 1470 125.9555 10.2171 1457.124 124.5249 2.289041 1470 124.9366 5.868247 1457.383 124.5249 -2.289041 1470 124.451 1.16853 1457.5 124.6153 -3.476717 1457.459 125.1224 -6.827959 1470 125.7639 -9.747233 1457.175 126.3073 -11.25006 1470 128.0592 -15.47967 1470 127.7005 -14.79562 1456.706 133.2743 -12.96516 1470 135.1817 -11.16393 1470 134.9654 11.27416 1470 137 -10.8 1470 138.8183 11.16393 1470 137 10.8 1470 133.6021 12.5313 1470 139.0346 -11.27416 1470 135.1817 18.83607 1470 133.2743 17.03484 1470 137 19.2 1470 139.0346 18.72584 1470 138.8183 -18.83607 1470 140.3979 17.4687 1470 140.3979 -12.5313 1470 140.7257 12.96516 1470 137 -19.2 1470 141.2102 15.54374 1470 140.7257 -17.03485 1470 133.6021 -17.4687 1470 132.7898 -15.54372 1470 134.9654 -18.72584 1470 141.2102 -14.45627 1470 132.7898 14.45629 1470 140.7257 -12.96516 1454 141.2102 -15.54374 1454 138.8183 -11.16393 1454 137 -10.8 1454 134.9654 -11.27416 1454 133.6021 -12.5313 1454 132.7898 -14.45629 1454 133.2743 -17.03484 1454 135.1817 -18.83607 1454 137 -19.2 1454 139.0346 -18.72584 1454 140.3979 -17.4687 1454 140.7257 17.03485 1454 141.2102 14.45627 1454 138.8183 18.83607 1454 137 19.2 1454 134.9654 18.72584 1454 133.6021 17.4687 1454 132.7898 15.54372 1454 133.2743 12.96516 1454 135.1817 11.16393 1454 137 10.8 1454 139.0346 11.27416 1454 140.3979 12.5313 1454 216.5099 -40.87759 1442.001 207.2183 -45.37147 1436.725 137.6248 -49.09999 1438.011 200.8406 -49.10647 1432.232 111 -49.1 1438.012 111 -38.65572 1451.954 111 -29.70489 1454.253 111 -20.61988 1455.945 111 -2.211895 1457.482 111 -11.44173 1457.023 111 7.02793 1457.32 111 16.23601 1456.538 111 25.37075 1455.139 111 34.39089 1453.13 111 43.25568 1450.519 111 53.6 1436.193 137.0498 53.6 1436.191 242.567 48.97928 1433.026 216.3612 53.6 1428.871 247.334 45.33001 1437.793 216.3612 53.6 1406.821 249.2574 38.01676 1439.717 164.5406 33 1355 164.5406 53.6 1355 250.3719 33 1440.831 260 33 1259.541 260 45.90531 1259.541 216.3612 53.6 1303.179 299.5879 40.51911 1421.984 299.3096 46.25509 1419.62 284.5298 43.62894 1425.927 299.6005 33.03855 1424.643 254.763 33 1439.397 279.028 33.00143 1431.432 269.9625 33 1434.416 355.4594 33 1355 343.233 54 1367.226 355.4594 53.99095 1355 327.2265 51.17756 1405.893 306.1659 47.4644 1416.383 343.2842 54.00569 1397.254 343.233 54 1342.774 278.6629 42.61454 1278.203 246.1157 48.35198 1250.201 278.6714 42.61603 1258.726 216.3612 53.6 1226.607 343.2835 54.00534 1289.164 334.9441 52.53843 1284.715 323.7108 50.55773 1279.476 300.3662 46.43708 1270.515 309.0375 47.97055 1273.629 259.8723 33 1444.506 170.5294 33 1355.163 259.8723 33 1265.82 349.2153 33 1355.163 170.5294 36 1355.163 259.8723 36 1444.506 349.2153 36 1355.163 259.8723 36 1265.82 246.0456 41.9088 1246.172 300.0247 35.41684 1262.083 246.0483 35.42515 1242.833 300.133 29.62969 1258.94 300.1139 23.67145 1256.389 246.0213 29.17115 1240.241 300.1176 17.47059 1254.415 246.0115 22.68567 1238.155 246.0142 15.94643 1236.584 246.0145 9.181798 1235.57 300.0438 11.27723 1253.068 300.2236 4.87565 1252.328 300.2249 -1.494837 1252.165 246.0352 2.423477 1235.123 246.1223 -6.77414 1235.352 300.0551 40.82881 1265.765 255.1147 -10.6599 1238.629 276.8872 -6.5 1245.085 300.1184 -6.5 1252.44 308.2361 -6.5 1250.734 311.1891 -6.501317 1253.9 261.409 -22.15805 1232.761 301.5751 -16.25858 1243.591 303.3131 -26.10767 1237.906 303.3131 -34.5 1237.906 252.5952 -34.49979 1231.556 237.3712 -34.49959 1212.036 237.3527 -24.50648 1212.171 237.9062 -34.5 1216.616 237.7531 -20.672 1216.041 238.9835 -34.5 1219.932 238.7325 -17.87295 1219.391 240.6202 -34.5 1223.01 240.2794 -15.77791 1222.522 242.7665 -34.5 1225.757 242.3444 -14.45233 1225.333 245.3573 -34.5 1228.09 245.3277 -13.89968 1228.13 248.838 -14.53371 1230.226 248.3138 -34.5 1229.937 252.4942 -16.11993 1231.55 211.7665 -6.845979 1209.004 238.1979 -33.62596 1204.343 238.1979 -34.5 1204.343 262.7949 -34.5 1200.006 284.7748 -34.5 1200.006 309.8114 -34.5 1216.651 302.4598 -34.5 1204.416 284.7748 -55.48398 1200.006 275.2113 -56.41976 1200.006 262.7949 -38.4837 1200.006 302.4598 -58.52966 1204.416 288.3298 -59.56246 1200.893 274.8866 -61.06241 1200.93 286.4747 -61.21953 1201.188 271.4743 -59.75791 1200.601 266.4906 -58.41595 1201.001 250.2199 -48.69086 1202.179 302.9463 -59.87584 1205.225 299.8133 -62.6745 1205.724 291.5459 -62.99261 1203.52 287.2717 -63.5 1204.161 275.8588 -63.56103 1204.293 303.0976 -63.4627 1211.289 306.2724 -60.62582 1210.761 309.4128 -57.26161 1215.987 309.8114 -56.30645 1216.651 302.417 -63.50164 1217.114 268.695 -62.14512 1205.675 300.9392 -62.19416 1220.665 308.6918 -54.43518 1220.313 299.8984 -59.76952 1223.494 264.268 -59.95598 1206.671 307.8464 -51.54579 1223.078 306.4964 -48.14429 1227.494 301.5751 -39.91945 1243.591 256.3457 -55.38433 1207.518 299.4449 -55.11781 1227.967 252.2049 -53.29473 1208.539 298.7586 -50.72878 1233.977 246.8403 -51.25855 1208.913 241.1059 -49.46821 1209.954 226.4869 -41.17141 1206.408 229.0865 -46.27593 1213.067 293.1794 -44.06156 1249.001 222.9645 -44.06156 1216.26 292.5611 -41.88559 1252.41 307.5703 -28.47828 1250.02 310.7986 -24.72601 1253.482 313.5556 -18.25064 1256.438 312.006 -12.08201 1254.777 315.3616 -23.251 1258.375 293.7277 -39.97494 1256.201 308.6085 -29.57668 1260.084 302.9615 -35.3103 1262.473 300.1812 -37.79383 1262.916 212.8074 -33.77027 1208.82 216.5245 -41.06889 1218.341 208.2556 -33.9994 1209.623 208.162 -28.57553 1209.64 210.0273 -20.48901 1209.311 211.2846 -12.42452 1209.089 206.2064 -35.09508 1209.984 209.7709 -36.96107 1213.486 213.5476 -40.51001 1217.903 323.3148 -41.79579 1266.904 320.5083 -33.19016 1263.894 323.6269 -37.60703 1267.238 326.2824 -40.73724 1270.086 358.006 41.46428 1276.297 358.0761 36.90432 1272.384 358.0638 31.92682 1268.911 358.0565 26.61044 1265.951 358.0553 21.02001 1263.541 358.0567 15.21815 1261.709 358.0629 9.262916 1260.472 358.0762 3.220346 1259.843 357.998 -2.768135 1259.821 357.9436 45.72665 1280.772 357.9377 49.46319 1285.602 357.8695 52.66988 1290.744 347.4693 -46.99432 1279.989 358.0233 -45.52648 1280.542 358.0842 -49.83849 1286.125 358.073 -41.33388 1276.172 330.4818 -42.44244 1272.254 358.1057 -36.72625 1272.248 358.2699 -31.91739 1268.912 322.3931 -40.27494 1269.058 358.112 -26.27937 1265.793 357.904 -20.69496 1263.418 357.9276 -14.90997 1261.626 357.9387 -8.927057 1260.418 603.5 44.18322 1289.272 603.5 47.05934 1293.89 603.5 40.85573 1284.969 603.5 37.11084 1281.024 603.5 32.98683 1277.477 603.5 28.52583 1274.364 603.5 23.7734 1271.718 603.5 18.77811 1269.565 603.5 13.59097 1267.927 603.5 8.264986 1266.821 603.5 2.854566 1266.258 603.5 -2.585015 1266.244 603.5 -7.998188 1266.78 603.5 -13.32965 1267.859 603.5 -18.52494 1269.471 603.5 -23.53097 1271.599 603.5 -28.29661 1274.222 603.5 -32.77317 1277.312 603.5 -36.91491 1280.838 603.5 -40.67953 1284.765 603.5 -44.02857 1289.051 603.5 -53.50931 1314.247 603.4989 -53.79899 1318.148 603.5 -52.65527 1308.875 590.7518 -53.73373 1313.188 603.5 -51.2633 1303.617 562.6074 -53.58244 1308.031 603.5 -49.34762 1298.526 506.6134 -53.2823 1301.556 368.1648 -52.53947 1291.052 603.5 -46.92781 1293.654 428.2679 -52.86202 1295.143 358.0164 53.99087 1293.246 603.5 49.4547 1298.773 478.739 53.89977 1301.176 603.5 51.34482 1303.874 547.5742 53.84925 1307.38 603.5 52.7104 1309.139 586.6129 53.81996 1313.059 603.5 53.53749 1314.516 603.4983 53.80174 1318.096 603.4999 54.66517 1324.548 603.5 39.62986 1282.11 603.5023 53.80607 1330.673 603.4999 54.67843 1315.079 603.4999 49.63021 1296.579 603.5 44.65216 1288.096 603.5 52.88475 1305.406 603.5 34.20968 1277.111 603.5 28.12157 1272.932 603.4999 21.55752 1269.551 603.5 12.63292 1266.595 603.5 4.914801 1265.392 603.5 -2.457454 1265.193 603.5 -37.91084 1280.344 603.5 -47.09734 1291.864 603.5 -54.64066 1315.082 603.4999 -54.71137 1324.161 603.4999 -25.62429 1271.471 603.5 -32.22747 1275.643 603.5 -42.86676 1285.815 603.5 -50.41646 1298.451 603.5 -9.790033 1266.052 603.5 -16.54749 1267.675 603.4999 -53.0157 1305.822 603.5023 -53.80037 1330.698 325.7177 -41.16587 1283.241 345.4216 -46.44545 1308.421 334.2671 -43.4565 1292.122 350.4463 -47.7917 1319.101 340.2443 -45.05815 1300.026 317.5932 -38.99573 1276.623 352.9799 -48.47069 1383.741 357.5427 -49.69297 1394.117 353.5825 -48.63211 1328.472 317.635 -39 1269.005 368.1801 -52.54291 1387.381 348.9709 -47.3964 1394.326 355.2858 -49.09194 1335.501 355.3995 -49.10602 1373.936 345.6257 -46.483 1401.105 356.6731 -49.1 1365.577 357.2122 -49.1 1357.712 357.1124 -49.1 1349.829 356.3745 -49.1 1341.98 192.5064 -49.1 1425.015 187.0571 -49.1 1419.319 182.0871 -49.1 1413.199 177.6291 -49.1 1406.697 173.7124 -49.1 1399.856 170.3628 -49.1 1392.719 167.6022 -49.1 1385.335 165.4487 -49.1 1377.751 163.9166 -49.1 1370.018 163.0159 -49.1 1362.186 162.7525 -49.1 1354.307 163.1281 -49.1 1346.433 164.1403 -49.1 1338.614 165.7825 -49.1 1330.904 168.0438 -49.1 1323.352 170.9093 -49.1 1316.008 174.3603 -49.1 1308.92 178.3741 -49.1 1302.134 182.9243 -49.1 1295.697 187.9809 -49.1 1289.649 193.5108 -49.1 1284.03 199.4777 -49.1 1278.878 206.5966 -49.10265 1273.705 214.9875 -47.64226 1268.714 225.0476 -45.86837 1264.227 234.4338 -44.21326 1261.109 245.9522 -42.18243 1258.724 256.1862 -40.37781 1257.801 264.1548 -38.99341 1257.823 273.4873 -39 1258.69 281.2438 -39 1260.099 288.8608 -39 1262.131 296.2881 -39 1264.774 303.4769 -39 1268.01 310.38 -39 1271.817 206.7219 -49.09983 1215.919 246.1355 -42.14968 1246.309 264.0542 -39.00043 1250.948 245.7985 -34.89294 1242.488 269.8434 -36.15932 1251.546 311.9877 -39 1266.372 300.2313 -37.49747 1263.44 300.1036 -39 1264.447 246.0187 -39.20571 1244.667 192.796 48.62076 1204.033 192.8131 40.43768 1200.936 192.8257 31.92034 1198.38 192.831 23.20101 1196.422 192.8304 14.34891 1195.084 192.8236 5.444732 1194.378 192.8095 -3.45932 1194.302 192.8266 -49.09822 1204.221 192.9132 53.60068 1206.278 192.802 -12.30975 1194.854 192.7892 -21.04027 1196.016 192.8055 -30.23966 1197.936 192.783 -38.74541 1200.366 151.8344 42.68218 1189.294 151.7859 53.59547 1193.326 151.8279 33.97214 1186.764 151.8187 25.12172 1184.815 151.8065 16.16371 1183.453 151.7933 7.173922 1182.687 151.7785 -1.831212 1182.512 151.8121 -11.19731 1182.956 151.8639 -20.27454 1184.009 151.7109 -28.91545 1185.578 151.7436 -37.50167 1187.715 151.7138 -49.09639 1191.505 130 45.41806 1190.218 130 53.6 1193.377 130 37.05131 1187.586 130 24.53471 1184.635 130 6.93581 1182.603 130 -10.75575 1182.849 130 -28.27883 1185.366 130 -40.81169 1188.696 130 -49.1 1191.565 644.5 -7.036686 1398.184 644.5 0 1398.5 603.4999 2.461518 1374.844 603.5 -7.357652 1374.366 644.5 -14.01672 1397.239 603.5 -14.58644 1372.853 644.5 -27.58292 1393.494 644.5 -20.88389 1395.671 603.4999 -21.9651 1370.292 644.5 -40.26259 1387.388 644.5 -34.05987 1390.726 603.5 -30.59099 1365.562 644.5 -51.64819 1379.116 644.5 -46.14114 1383.508 644.5 -56.73939 1374.248 603.5 -37.91157 1359.655 603.5 -42.86676 1354.185 644.5 -65.514 1363.245 644.5 -61.37377 1368.944 603.5 -47.09735 1348.136 644.5 -69.12675 1357.199 603.4999 -51.39903 1339.289 644.5 -74.65795 1344.258 644.5 -72.18293 1350.852 644.5 -76.53184 1337.468 644.5 -77.78956 1330.537 644.5 -78.42096 1323.522 644.5 -78.42096 1316.478 644.5 -77.78956 1309.463 644.5 -76.53184 1302.532 644.5 -74.65795 1295.742 644.5 -69.12675 1282.801 644.5 -72.18293 1289.148 644.5 -65.514 1276.755 644.5 -56.73939 1265.752 644.5 -61.37377 1271.056 644.5 -51.64819 1260.884 644.5 -40.26259 1252.612 644.5 -46.14114 1256.492 644.5 -27.58292 1246.506 644.5 -34.05987 1249.274 644.5 -14.01672 1242.761 644.5 -20.88389 1244.329 644.5 -7.036686 1241.816 644.5 0 1241.5 644.5 14.01672 1242.761 644.5 7.036686 1241.816 644.5 27.58292 1246.506 644.5 20.88389 1244.329 644.5 34.05987 1249.274 644.5 46.14114 1256.492 644.5 40.26259 1252.612 644.5 51.64819 1260.884 644.5 61.37377 1271.056 644.5 56.73939 1265.752 644.5 69.12675 1282.801 644.5 65.514 1276.755 644.5 74.65795 1295.742 644.5 72.18293 1289.148 644.5 76.53184 1302.532 644.5 78.42096 1316.478 644.5 77.78956 1309.463 644.5 78.42096 1323.522 644.5 77.78956 1330.537 644.5 76.53184 1337.468 603.4999 51.39902 1339.289 644.5 74.65795 1344.258 644.5 69.12675 1357.199 644.5 72.18293 1350.852 644.5 65.514 1363.245 603.5 47.09732 1348.136 603.5 42.86676 1354.185 644.5 56.73939 1374.248 644.5 61.37377 1368.944 603.5 37.9112 1359.655 644.5 51.64819 1379.116 603.4999 30.24099 1365.82 644.5 46.14114 1383.508 644.5 34.05987 1390.726 644.5 40.26259 1387.388 603.4999 21.16419 1370.634 644.5 20.88389 1395.671 644.5 27.58292 1393.494 644.5 14.01672 1397.239 603.5 12.21456 1373.484 644.5 7.036686 1398.184 603.5 53.80737 1332.157 603.5 52.58271 1336.676 603.5 48.16377 1346.894 603.5 45.20425 1351.617 603.5 41.78331 1356.017 603.5 37.93587 1360.049 603.5 33.70119 1363.672 603.5 29.1225 1366.85 603.5 19.1231 1371.743 603.5 13.80444 1373.409 603.5 50.63165 1341.897 603.5 24.24655 1369.549 603.5 -19.09778 1371.752 603.5 -24.22231 1369.561 603.5 -29.09959 1366.864 603.5 -33.67982 1363.689 603.5 -37.91627 1360.067 603.5 -41.76569 1356.037 603.5 -45.18878 1351.639 603.5 -48.15061 1346.918 603.5 -52.57455 1336.702 603.5 -50.62094 1341.922 603.4998 -53.80023 1332.321 603.5 8.344881 1374.529 603.5 2.800136 1375.093 603.5 -2.77319 1375.094 603.5 -8.318208 1374.533 603.5 -13.77832 1373.415 489.833 53.89259 1342.31 472.6484 53.90447 1348.388 380.2964 53.97222 1380.7 401.8945 53.95637 1369.939 444.3184 53.92495 1356.55 569.5266 53.83156 1335.89 411.8571 53.95058 1364.578 490.0752 -53.19352 1343.798 397.2997 -52.69601 1373.617 476.4439 -53.11989 1348.586 411.7278 -52.77764 1366.061 454.5471 -53.00278 1355.155 543.8977 -53.48222 1339.193 662 -7.036686 1241.816 662 -14.01672 1242.761 662 -20.88389 1244.329 662 -27.58292 1246.506 662 -34.05987 1249.274 662 -40.26259 1252.612 662 -46.14114 1256.492 662 -51.64819 1260.884 662 -56.73939 1265.752 662 -61.37377 1271.056 662 -65.514 1276.755 662 -69.12675 1282.801 662 -72.18293 1289.148 662 -74.65795 1295.742 662 -76.53184 1302.532 662 -77.78956 1309.463 662 -78.42096 1316.478 662 -78.42096 1323.522 662 -77.78956 1330.537 662 -76.53184 1337.468 662 -74.65795 1344.258 662 -72.18293 1350.852 662 -69.12675 1357.199 662 -65.514 1363.245 662 -61.37377 1368.944 662 -56.73939 1374.248 662 -51.64819 1379.116 662 -46.14114 1383.508 662 -40.26259 1387.388 662 -34.05987 1390.726 662 -27.58292 1393.494 662 -20.88389 1395.671 662 -14.01672 1397.239 662 -7.036686 1398.184 662 0 1398.5 662 7.036686 1398.184 662 14.01672 1397.239 662 20.88389 1395.671 662 27.58292 1393.494 662 34.05987 1390.726 662 40.26259 1387.388 662 46.14114 1383.508 662 51.64819 1379.116 662 56.73939 1374.248 662 61.37377 1368.944 662 65.514 1363.245 662 69.12675 1357.199 662 72.18293 1350.852 662 74.65795 1344.258 662 76.53184 1337.468 662 77.78956 1330.537 662 78.42096 1323.522 662 78.42096 1316.478 662 77.78956 1309.463 662 76.53184 1302.532 662 74.65795 1295.742 662 72.18293 1289.148 662 69.12675 1282.801 662 65.514 1276.755 662 61.37377 1271.056 662 56.73939 1265.752 662 51.64819 1260.884 662 46.14114 1256.492 662 40.26259 1252.612 662 34.05987 1249.274 662 27.58292 1246.506 662 20.88389 1244.329 662 14.01672 1242.761 662 7.036686 1241.816 662 0 1241.5 489.9461 -47.76772 1353.406 489.9747 -44.17851 1358.023 489.9779 -40.09368 1362.309 490.0379 -35.71792 1366.057 490.0348 -30.65904 1369.574 489.7743 -25.46616 1372.435 490.0515 -19.96341 1374.756 490.0915 -14.18379 1376.523 489.9916 -8.482949 1377.661 489.8941 25.46638 1372.431 489.9838 30.72607 1369.532 490.0097 35.52473 1366.209 489.8983 39.80059 1362.576 489.8929 44.22714 1357.974 489.9758 47.78495 1353.38 489.9219 50.88445 1348.439 489.8856 8.839678 1377.619 512.0151 5.764462 1377.399 511.2082 2.691328 1377.65 489.9412 3.001484 1378.208 489.9374 14.57456 1376.44 518.0703 13.79839 1375.844 515.4393 11.38307 1376.456 513.4336 8.658614 1376.991 542.921 14.50029 1374.949 539.7567 16.24996 1374.551 536.4089 17.39503 1374.293 531.9973 18.06587 1374.201 489.9456 20.16974 1374.691 524.077 16.95333 1374.789 527.5326 17.79265 1374.421 520.7033 15.48493 1375.316 547.8616 9.7741 1375.845 545.5099 12.46093 1375.38 550.8271 2.467397 1376.565 549.7951 6.356386 1376.299 550.9249 -0.7318087 1376.611 514.4694 -3.929929 1377.481 512.4879 -2.629081 1377.614 489.9302 -2.927989 1378.217 518.5586 -5.457337 1377.244 531.7293 -6.974211 1376.713 538.804 -6.425607 1376.582 524.556 -6.607536 1376.956 545.2525 -4.914058 1376.558 549.3898 -2.773145 1376.589 511.0598 -0.7715009 1377.709 489.9296 -50.88006 1348.446 550.6807 3.250958 1381 550.9949 -0.2966403 1381 549.7328 6.352489 1381 548.1867 9.252655 1381 546.0916 11.85883 1381 543.5147 14.08779 1381 540.538 15.86834 1381 537.2568 17.14363 1381 533.7758 17.87292 1381 530.2061 18.03293 1381 526.6617 17.61854 1381 523.2559 16.643 1381 520.0974 15.13744 1381 514.9147 10.74403 1381 517.2871 13.14996 1381 513.0561 7.996487 1381 511.7705 4.995069 1381 511.099 1.835634 1381 511.0401 -0.491705 1381 511.6169 -1.678022 1381 513.4385 -3.352239 1381 517.8671 -5.260557 1381 523.9644 -6.53269 1381 531.0975 -6.978826 1381 538.2222 -6.508976 1381 543.0498 -5.53978 1381 547.1473 -4.120598 1381 550.1798 -2.029078 1381 411.9566 50.98172 1367.889 412.0378 46.3916 1372.302 411.9018 41.34342 1376.437 411.9639 35.58818 1380.213 411.9088 30.16617 1383.095 411.8046 23.55325 1385.892 411.934 16.07785 1388.092 398.6745 16.07605 1392.898 402.0939 9.371484 1392.898 403.6954 0.9476228 1392.898 403.127 -5.314886 1392.898 401.5359 -10.4431 1392.898 411.9789 -15.27913 1388.25 411.957 -10.44466 1389.163 411.8215 -21.65165 1386.521 411.9108 -28.23022 1383.988 411.9664 -33.72895 1381.273 412.0022 -39.21206 1377.887 411.9216 -44.44699 1374.024 411.9524 -49.49905 1369.421 464.8966 -10.36602 1392.898 465.0439 -10.34978 1381.143 458.2121 15.99474 1380.97 467.007 11.76583 1380.594 463.2079 14.41196 1380.6 471.5316 4.132214 1380.916 469.6859 8.488004 1380.746 472.0299 0.2529429 1380.971 471.8431 -2.458733 1380.949 470.8318 -5.971996 1380.861 467.1627 -9.639965 1380.939 469.0913 -8.328968 1380.844 470.8489 -5.988094 1392.898 467.4549 -9.461215 1392.898 459.007 15.7912 1392.898 456 16.07605 1392.898 461.907 14.94681 1392.898 466.9809 11.71835 1392.898 464.5968 13.5729 1392.898 471.8805 -2.001734 1392.898 471.9856 1.016867 1392.898 468.9743 9.449138 1392.898 471.522 4.001498 1392.898 470.5061 6.845985 1392.898 469.0745 -8.289414 1392.898 130 53.6 1268.005 124 53.6 1268.005 124 53.6 1272.555 111 53.6 1272.555 111 -49.1 1272.555 130 -49.1 1268.005 124 -49.1 1272.555 124 -49.1 1268.005 130 36.25 1191.299 130 -36.25 1191.299 130 -36.25 1263.799 130 36.25 1263.799 127 36.25 1191.299 127 36.25 1263.799 127 -36.25 1191.299 127 -36.25 1263.799 111 -36.12185 1448.827 111 36.37815 1448.827 111 -36.12185 1376.327 111 46.72144 1274.929 111 46.72144 1365.079 111 -46.57855 1274.929 111 -46.57855 1365.079 111 36.37815 1376.327 103.5 46.72144 1365.079 103.5 -46.57855 1365.079 103.5 -46.57855 1274.929 103.5 46.72144 1274.929 108 36.37815 1376.327 108 36.37815 1448.827 108 -36.12185 1376.327 108 -36.12185 1448.827 103.5 36.25 1283.749 103.5 36.25 1356.249 103.5 -36.25 1283.749 103.5 -36.25 1356.249 100.5 36.25 1283.749 100.5 36.25 1356.249 100.5 -36.25 1283.749 100.5 -36.25 1356.249 + + + + + + + + + + -2.30476e-5 0 1 0 0 1 -3.01692e-5 0 1 -2.3047e-5 0 1 2.06667e-5 0 1 -0.8776323 -0.4793155 0.004274368 -0.4283282 -0.9036132 0.004274606 0.1846042 -0.9828037 0.004274666 0.7270436 -0.686578 0.004272699 0.9805433 -0.1963028 0 0.9738875 0.2270018 0.003641843 0.6866015 0.7270213 0.0042755 0.1281124 0.9917504 0.004274666 -0.4792992 0.8776412 0.004274368 -0.8718777 0.4896865 -0.006044268 -0.9963434 0.08503192 0.008334159 -0.8776323 0.4793155 -0.004274368 -0.4283282 0.9036132 -0.004274487 0.1846042 0.9828037 -0.004274666 0.7270436 0.686578 -0.004272758 0.9805433 0.1963028 0 0.9738875 -0.2270018 -0.003641843 0.6866015 -0.7270213 -0.0042755 0.1281138 -0.9917502 -0.004274845 -0.4793037 -0.8776388 -0.004274427 -0.8718777 -0.4896865 0.006044149 -0.9963434 -0.08503192 -0.008334159 -9.7098e-5 0 1 9.65538e-5 0 1 -1.17207e-4 0 1 -6.96745e-5 0 1 7.27442e-5 0 1 -5.18857e-5 0 1 2.9057e-5 0 1 1.1699e-4 0 1 5.31304e-5 0 1 4.64811e-5 0 1 -2.60522e-5 0 1 4.36297e-5 0 1 5.88281e-5 0 1 2.95388e-5 0 1 -9.08812e-5 0 1 -2.26751e-5 0 1 -3.39366e-5 0 1 5.68584e-5 0 1 2.95692e-5 0 1 -2.36324e-5 0 1 -9.39423e-5 0 1 2.85256e-5 0 1 2.99139e-5 0 1 6.00497e-5 0 1 -5.671e-5 0 1 -2.88913e-5 0 1 -7.1027e-5 0 1 -5.50545e-5 0 1 2.96278e-5 0 1 2.86391e-5 0 1 3.70024e-5 0 1 -2.77601e-5 0 1 -0.7456244 -0.6663396 0.005988895 -0.5320511 -0.8467057 -0.003334462 -0.5758119 -0.8175712 0.004259824 -0.2768368 -0.9609159 -0.001479625 -0.3207518 -0.9471535 0.004312336 0 -0.9999988 -0.001573979 -0.04668331 -0.9989009 0.00420928 0.2768534 -0.960911 -0.001469075 0.2351986 -0.9719403 0.003704607 0.5320518 -0.8467108 -0.001374542 0.4921743 -0.8704876 0.00397557 0.7456452 -0.6663416 -0.001459777 0.7091825 -0.7050103 0.00456959 -0.8462762 0.5326945 -0.007302999 -0.9326232 0.3608417 0.00269401 -0.9659031 0.2588117 0.006913304 -0.9914427 0.1305027 0.003236174 -0.9845439 0.1750399 -0.005871236 -0.9996948 0.02424073 0.004766285 -0.9999978 0 -0.002114951 -0.9954432 -0.09532457 -0.002482175 -0.9914377 -0.1305204 0.003958642 -0.9732205 -0.2298633 -0.002152085 -0.9659198 -0.2588143 0.003776013 -0.9238806 -0.3826774 -0.001668512 -0.9296727 -0.3683769 0.002672553 -0.8660349 -0.4999802 0.001902222 -0.8465271 -0.5322971 -0.007196545 -0.9238724 0.3826665 -0.005126476 -0.8660345 0.4999808 0.001903057 -0.3197685 0.947486 0.004289269 -0.5841621 0.8116272 0.004022181 0.7092109 0.7049817 0.004560947 0.4925798 0.8702583 0.003972887 0.2382997 0.971185 0.003591477 -0.04637694 0.9989153 0.004184961 0 0.9999988 -0.001556634 0.2768511 0.9609122 -0.001160621 0.5320556 0.8467085 -0.001305818 0.745639 0.6663486 -0.001464009 -0.7456476 0.6663206 0.005147218 -0.5320513 0.8466957 -0.005295217 -0.2768393 0.9609155 -0.001291811 0.866031 -0.4999887 -0.001323163 0.8571884 -0.5149971 0.002447962 0.9238849 -0.38267 6.92124e-4 0.9659126 -0.2588205 0.004988849 0.9914371 -0.1305062 -0.004545748 0.9878079 -0.1556674 0.001829445 0.9999977 0 0.002151072 0.986123 0.165957 0.004445552 0.9354004 0.3535475 -0.005512177 0.8571945 0.5149871 0.002449929 0.8660302 0.4999902 -0.001320838 0.9238789 0.3826845 6.91125e-4 0.9659115 0.2588247 0.004987478 0.9914347 0.1305246 -0.004553139 0.9997299 0.02316969 -0.001859724 0.9354023 -0.3535425 -0.005513489 -0.877635 -0.4793106 0.004274308 -0.4283329 -0.9036109 0.004274487 0.1846014 -0.9828042 0.004274666 0.7270436 -0.686578 0.004272758 0.9738875 0.2270018 0.003641843 0.6866139 0.7270097 0.004275441 0.1281138 0.9917502 0.004274845 -0.4792992 0.8776412 0.004274487 -0.8718737 0.4896935 -0.006044268 -0.9963434 0.08503317 0.008334279 -0.4283376 0.9036086 -0.004274547 0.7270436 0.686578 -0.004272699 0.980544 0.1962997 0 0.9738875 -0.2270018 -0.003641843 0.6866077 -0.7270156 -0.004275441 0.1281153 -0.9917501 -0.004274666 -0.4792992 -0.8776412 -0.004274368 -0.8718777 -0.4896865 0.006044268 -0.9963434 -0.08503317 -0.008334279 2.30476e-5 0 1 -1.2067e-4 0 1 -6.12598e-5 0 1 3.2688e-5 0 1 -4.6094e-5 0 1 -0.2017524 0 0.9794366 -0.124394 0 0.9922329 -0.04628968 0 0.9989281 0.03225946 0 0.9994795 0.4820251 0 0.8761575 0.5492584 0 0.8356527 0.6130618 0 0.790035 0.6731073 0 0.7395448 0.7797374 -0.04030632 0.624808 0.8022582 0.0137127 0.5968198 0.7741472 -0.0106303 0.6329166 0.7197842 0 0.694198 0.7502931 0.002663731 0.6611 0.7289127 -0.01426005 0.6844583 0.3572872 0.002811014 0.9339904 0.3293366 0.1371766 0.9341949 0.3391203 0.04214435 0.9397986 0.3481655 0.01363086 0.9373341 0.3964784 -0.005481481 0.9180277 0.4130237 -0.001956701 0.9107182 0.4271469 0 0.9041823 0.4241477 5.49111e-4 0.9055929 0.4158881 0.002696692 0.9094118 0.4118523 -0.003427207 0.9112442 0.4026542 0.008236885 0.9153152 0.3211486 -0.01052445 0.9469704 0.3395106 -0.004344046 0.9405922 0.3548609 -0.001036703 0.9349187 0.2505007 -0.001780033 0.9681149 0.2643955 -0.004002332 0.9644061 0.2725045 -0.007575333 0.9621248 0.2996517 4.63749e-4 0.9540486 0.1583222 -1.05095e-4 0.9873875 0.1443465 6.61534e-5 0.9895272 0.1712362 -8.63069e-4 0.9852297 0.1956279 -0.004882514 0.9806661 0.1879863 -0.001578032 0.9821705 0.1096895 -1.85436e-4 0.9939659 0.1104933 7.22694e-6 0.9938769 0.110512 0 0.9938749 0.155422 1.20781e-4 0.9878482 0.1688459 0.0013507 0.9856416 0.1879144 0.01026904 0.9821317 0.2308652 -0.003689587 0.9729788 0.2446507 0.02199232 0.9693619 -0.2808878 -0.004020512 0.9597323 -0.2435613 0 0.9698855 -0.2517193 2.99723e-4 0.9678003 -0.2581025 -3.98474e-4 0.9661175 -0.2682636 0.003762781 0.9633383 -0.2732153 0.01148283 0.9618844 -0.3303511 6.67975e-4 0.9438579 0.8225342 -0.004585087 0.5686972 0.826334 -0.07066088 0.5587301 -0.3484646 -0.01218658 0.9372428 -0.2778812 -0.002396225 0.9606125 0.2413373 0.3111222 0.9192168 0.1879836 0.01051694 0.9821159 0.1105197 2.90888e-5 0.993874 0.2294071 3.07929e-4 0.9733306 0.3392385 -0.001286864 0.9406995 0.4118822 0.001179635 0.9112364 0.7198994 1.82816e-5 0.6940785 0.6731261 0 0.7395278 0.6130831 0 0.7900185 0.4819989 0 0.8761719 -0.04625564 0 0.9989297 -0.2017524 0 0.9794366 -0.6251375 -0.7804383 -0.01091599 -0.4630207 -0.8861049 0.02073723 -0.2375897 -0.9713626 -0.00246936 -0.2623752 -0.9649342 0.007826089 -0.02661615 -0.9996458 1.2841e-4 -0.04943585 -0.9987598 0.005918383 0.1658009 -0.9861593 -1.48025e-4 0.1364285 -0.9906297 0.006327807 0.373331 -0.9276952 -0.002399802 0.3400522 -0.9403865 0.006157279 0.5635055 -0.8261094 -0.002235352 0.5322134 -0.8465867 0.006331562 0.7080948 -0.7061124 -0.002670168 0.7275161 -0.6860849 0.002790987 0.8708401 -0.4915522 0.003760814 0.9608197 -0.2770985 0.006473898 0.994149 -0.1078042 0.006794691 0.94794 -0.3184144 -0.004705667 0.8576706 -0.5141946 -0.002273976 -0.4352167 -0.9003007 -0.006730079 1 0 0 0.999908 -0.01097035 -0.007981657 1 -6.34607e-6 1.68567e-5 1 4.26417e-6 9.38348e-6 0.999952 0.008261978 -0.005266487 1.61766e-5 0 1 2.51251e-5 0 1 -2.568e-5 0 1 -1.5558e-5 0 1 -1.22703e-5 0 1 1.62703e-5 0 1 2.54552e-5 0 1 7.24841e-5 0 1 -2.7611e-5 0 1 2.1314e-5 0 1 -7.17774e-5 0 1 -1.60718e-5 0 1 1.07921e-5 0 1 -7.25441e-5 0 1 3.27205e-5 0 1 -1.89166e-4 -9.06228e-5 1 -9.42784e-4 0.001861572 0.9999979 7.53601e-5 0 1 1.5702e-4 0 1 -8.04226e-6 0 1 -3.67806e-5 0 1 -1.20853e-4 0 1 3.65036e-6 0 1 1.78714e-5 0 1 0.994498 0.1045269 0.006927728 0.9510377 0.3090017 -0.006737768 0.9668039 0.2554073 0.007585763 0.8660203 0.5000008 -0.002880156 0.8843064 0.4668745 0.00551629 0.7431558 0.6691159 -0.00185281 0.7562727 0.6542526 0.002263426 0.5675249 0.8233501 0.003202676 0.3747008 0.9271297 0.00547707 0.1743784 0.9846625 0.005658268 -0.03348672 0.9994214 0.005972981 -0.2399235 0.9707702 0.00647813 -0.4308245 0.9024092 0.006931245 -0.5805698 0.8142107 7.28059e-5 -0.7583846 0.6517795 0.006034553 -0.8785326 0.4775545 0.01105338 -0.9512839 0.3083158 4.4201e-4 -0.9972047 0.07081997 0.02382105 -0.9510651 0.3089907 -4.84052e-5 -0.8660215 0.5000068 -4.87211e-4 -0.7431269 0.6691372 -0.004216492 -0.5877865 0.8090108 0.002945899 -0.4067337 0.9135468 -9.49374e-5 -0.2079017 0.9781463 -0.002643048 0 0.9999973 -0.00238353 0.2079156 0.9781444 -0.002188682 0.4067394 0.9135419 -0.002065002 0.587772 0.8090243 -0.001984 -0.9995043 0.02788072 -0.01462191 -2.54761e-5 1 3.28824e-5 -8.94553e-6 1 7.03663e-5 1.15495e-5 1 1.03823e-4 -3.77394e-6 1 8.16028e-5 -3.93915e-4 1 4.71046e-5 2.98482e-6 1 9.25586e-5 3.20473e-5 1 1.68731e-4 2.20225e-5 1 1.15048e-4 7.23044e-5 1 1.31447e-4 8.2553e-4 0.9999995 7.57279e-4 4.03353e-4 0.9999998 5.20469e-4 0 1 0 -1.64251e-4 0.9999999 -6.63667e-4 2.64437e-4 0.9999999 4.01656e-4 6.0667e-5 1 1.3403e-4 5.60067e-4 0.9999998 6.15032e-4 6.3244e-4 0.9999997 6.08787e-4 0 -1 0 0 -1 1.70111e-6 0 -1 1.73275e-6 -0.002351403 -0.9999961 -0.001579046 0 -1 -3.47768e-6 0 -1 1.73049e-6 -0.001087427 -0.9999971 -0.002158045 0 -1 -1.74182e-6 -7.06208e-4 -0.9999996 6.88274e-4 0 -1 -1.8384e-6 0 -1 -1.83901e-6 -0.04081296 0 -0.9991669 -0.1220377 0 -0.9925256 -0.2025943 0 -0.9792628 -0.2817716 0 -0.9594815 -0.3589701 0 -0.9333491 -0.4338372 0 -0.9009914 -0.5059024 0 -0.8625908 -0.5744618 0 -0.8185315 -0.6393499 0 -0.7689159 -0.6998254 0 -0.714314 -0.7557462 0 -0.6548647 -0.8066418 0 -0.5910409 -0.8520799 0 -0.5234117 -0.8919507 0 -0.4521329 -0.9258194 0 -0.3779665 -0.9535374 0 -0.3012747 -0.9749325 0 -0.222501 -0.9898226 0 -0.1423069 -0.9981278 0 -0.06116467 -0.999792 0 0.02040052 -0.9948031 0 0.1018171 -0.9831959 0 0.1825538 -0.9650318 0 0.2621332 -0.9404743 0 0.3398651 -0.9096229 0 0.415435 -0.8727561 0 0.4881567 -0.8300466 0 0.5576942 -0.781839 0 0.6234805 -0.7284001 0 0.6851521 -0.6700961 0 0.7422744 -0.6074663 0 0.7943455 -0.5405505 0 0.8413117 -0.4703279 0 0.8824918 -0.3967816 0 0.9179131 -0.32068 0 0.9471876 -0.2423173 0 0.9701971 -0.1624758 0 0.9867126 -0.08153909 0 0.9966702 0.0815677 0 0.9966678 0.16242 0 0.9867218 0.2423443 0 0.9701903 0.3206281 -0.001252174 0.9472045 0.891951 0 -0.4521322 0.8520879 0 -0.5233989 0.8066609 0 -0.5910146 0.7557539 0 -0.6548557 0.6997881 0 -0.7143505 0.639351 0 -0.7689152 0.5744811 0 -0.8185179 0.5059513 0 -0.8625621 0.4338325 0 -0.9009936 0.3589945 0 -0.9333397 0.2818252 0 -0.9594658 0.2025967 0 -0.9792622 0.1220646 0 -0.9925222 0.04075539 0 -0.9991691 0.3967872 0.001391172 0.9179097 0.4260292 0.003059983 0.9047043 0.4703095 0 0.8825016 0.5405681 0 0.8413004 0.6074655 0 0.7943461 0.6701073 0 0.7422643 0.728404 0 0.685148 0.7818312 0 0.6234902 0.8300498 0 0.5576894 0.8727494 0 0.4881685 0.9096217 0 0.4154376 0.9404753 0 0.3398622 0.9650334 0 0.2621273 0.9831931 0 0.1825688 0.9948036 0 0.1018126 0.9997922 0 0.02038633 0.9981278 0 -0.06116509 0.9898225 0 -0.1423078 0.9749317 0 -0.2225043 0.9535383 0 -0.3012718 0.9325575 0.002841413 -0.3610107 0.9328814 0 -0.360184 0.9258325 0.001546561 -0.3779309 0.9535347 0 -0.3012832 0.9749298 0 -0.2225129 0.9898217 0 -0.1423133 0.9997922 0 0.02038711 0.9948033 0 0.1018166 0.9831945 0 0.1825617 0.9650307 0 0.2621374 0.9404662 0 0.3398875 0.8727588 0 0.4881517 0.8300744 0 0.5576528 0.7818312 0 0.6234903 0.7284226 0 0.6851282 0.6074656 0 0.7943461 0.54054 0 0.8413183 0.4703403 0 0.8824852 0.4095149 0 0.9123035 0.0408129 0 -0.9991669 0.1220362 0 -0.9925256 0.2817721 0 -0.9594814 0.3589694 0 -0.9333494 0.4338325 0 -0.9009935 0.5059084 0 -0.8625872 0.5744618 0 -0.8185315 0.6998175 0 -0.7143216 0.7557539 0 -0.6548558 0.8066408 0 -0.5910421 0.8520799 0 -0.5234117 0.8983234 -0.001585125 -0.439332 0.328625 0 0.9444605 0.2423173 0 0.9701971 0.1624761 0 0.9867125 0.08153909 0 0.9966702 -0.0815677 0 0.9966678 -0.1624197 0 0.9867218 -0.2423443 0 0.9701903 -0.3206283 0 0.9472052 -0.3967573 0 0.9179235 -0.4703279 0 0.8824918 -0.5405709 0 0.8412985 -0.6074662 0 0.7943455 -0.670112 0 0.7422601 -0.7284136 0 0.6851377 -0.781839 0 0.6234804 -0.8300555 0 0.557681 -0.8727629 0 0.4881444 -0.909618 0 0.4154458 -0.9404709 0 0.3398743 -0.9650298 0 0.2621405 -0.9831979 0 0.1825435 -0.9948035 0 0.1018142 -0.9898214 0 -0.142315 -0.9749296 0 -0.2225135 -0.9535348 0 -0.301283 -0.8919566 0 -0.4521211 -0.8520879 0 -0.5233989 -0.8066619 0 -0.5910133 -0.7557461 0 -0.6548648 -0.6997961 0 -0.7143427 -0.6393499 0 -0.768916 -0.5744811 0 -0.8185179 -0.5059453 0 -0.8625656 -0.3589951 0 -0.9333395 -0.2818247 0 -0.959466 -0.2025944 0 -0.9792628 -0.122066 0 -0.992522 -0.04075545 0 -0.9991692 0 -1 2.28865e-6 0 -1 5.71919e-7 0 -1 1.14487e-6 0 -1 -5.72098e-7 0 -1 -1.14418e-6 0 -1 -2.11063e-6 0 -1 -1.05455e-6 0 -1 1.0552e-6 0 -1 5.74227e-7 0 -1 -2.8675e-7 0 -1 2.86396e-7 0 -1 -8.58556e-7 0 -1 1.05081e-6 0 -1 -1.14879e-6 0 -1 1.14714e-6 0 -1 2.29013e-6 0 -1 7.90339e-7 0 -1 -1.05245e-6 0 -1 7.91114e-7 0 -1 -2.10846e-6 0 -1 -1.14541e-6 0 -1 5.27762e-7 0 -1 1.05118e-6 0 -1 -7.89548e-7 0 -1 1.14634e-6 0 -1 -5.72038e-7 0 -1 1.14984e-6 0 -1 -5.71965e-7 0 -1 -1.05373e-6 0 -1 -1.14985e-6 0 -1 -1.14453e-6 0 -1 -1.05019e-6 0 -1 5.72003e-7 0 -1 -1.58357e-6 0 -1 2.29064e-6 0 -1 1.05533e-6 0 -1 5.72148e-7 0 -1 2.28768e-6 0 -1 1.05309e-6 -0.3821181 0 -0.9241135 -0.3828181 -8.59537e-4 -0.9238234 -0.3827579 -0.001301825 -0.9238478 -0.3827305 1.28073e-4 -0.9238601 -0.9238786 -0.001203596 0.3826842 -0.9238871 1.31749e-4 0.3826652 -0.9236285 0 0.3832893 -0.9236564 -0.005318522 0.3831849 -0.04423779 0 0.9990211 -0.1324086 0 0.9911953 -0.2194248 0 0.9756295 -0.3047807 0 0.9524226 -0.387722 0 0.9217764 -0.4678273 0 0.8838199 -0.5440179 0 0.8390736 -0.6160619 0 0.7876977 -0.6832805 0 0.730156 -0.7450859 0 0.6669686 -0.8011572 0 0.5984541 -0.8508927 0 0.5253397 -0.8939957 0 0.4480758 -0.9301097 0 0.3672819 -0.9589266 0 0.2836546 -0.9802401 0 0.1978116 -0.9938878 0 0.1103955 -0.9997556 0 0.02211022 -0.9977985 0 -0.06631976 -0.9880315 0 -0.1542527 -0.9705333 0 -0.2409675 -0.9454332 0 -0.3258163 -0.9129354 0 -0.4081043 -0.8733105 0 -0.4871641 -0.8268436 0 -0.562432 -0.7738883 0 -0.6333221 -0.7148418 0 -0.6992863 -0.6503524 0 -0.7596328 -0.580588 0 -0.8141975 -0.5062978 0 -0.8623587 -0.4282554 0 -0.9036578 -0.3465731 0 -0.938023 -0.2623638 0 -0.9649691 -0.1760408 0 -0.9843829 -0.08404302 -0.003125429 -0.9964573 0.01278012 0 -0.9999184 0 0.00744605 -0.9999723 0.08844822 0 -0.9960808 0.176067 0 -0.9843782 0.2624165 0 -0.9649547 0.3466199 0 -0.9380058 0.4282614 0 -0.903655 0.5062918 0 -0.8623623 0.580588 0 -0.8141975 0.6503373 0 -0.7596456 0.7148687 0 -0.6992587 0.7738661 0 -0.6333492 0.8268502 0 -0.5624222 0.8733254 0 -0.4871373 0.3047807 0 0.9524226 0.2194252 0 0.9756294 0.132381 0 0.9911989 0.04421025 0 0.9990223 0.9435619 0.005008637 -0.3311584 0.970534 0 -0.2409647 0.9880291 0 -0.1542685 0.9977993 0 -0.06630778 0.9997556 0 0.02211022 0.9938875 0 0.1103984 0.9802396 0 0.1978142 0.958926 0 0.2836565 0.9301103 0 0.3672804 0.8940008 0 0.4480655 0.8508964 0 0.5253335 0.8011535 0 0.598459 0.7450789 0 0.6669764 0.6832809 0 0.7301556 0.6160648 0 0.7876955 0.5440015 0 0.8390843 0.4678162 0 0.8838258 0.4250442 -0.02665549 0.90478 0.4067767 0 0.9135277 0.3876979 -0.009712696 0.9217354 0.9129161 -0.006256759 -0.4080993 0.9101216 0.004608869 -0.4143157 0.9094935 0 -0.4157181 0.5439772 0 0.8391001 0.6160434 0 0.7877123 0.6832993 0 0.7301384 0.8011411 0 0.5984756 0.8939939 0 0.4480793 0.9589287 0 0.2836471 0.9997556 0 0.02211099 0.9705359 0 -0.2409567 0.9454389 0 -0.3257998 0.04423779 0 0.9990211 0.1324082 0 0.9911953 0.3196076 0.0110628 0.9474854 0.8733123 0 -0.4871608 0.8268416 0 -0.562435 0.7738883 0 -0.6333221 0.7148418 0 -0.6992863 0.6503533 0 -0.759632 0.3465713 0 -0.9380236 0.2623651 0 -0.9649687 0.1760402 0 -0.984383 -0.08844786 0 -0.9960808 -0.1760676 0 -0.9843782 -0.2624152 0 -0.9649552 -0.3466216 0 -0.9380052 -0.6503365 0 -0.7596463 -0.7148687 0 -0.6992587 -0.7738661 0 -0.6333492 -0.8268523 0 -0.5624192 -0.8733236 0 -0.4871407 -0.9454389 0 -0.3257997 -0.9705365 0 -0.2409546 -0.9977983 0 -0.06632155 -0.9997556 0 0.02211081 -0.9938875 0 0.1103985 -0.9802391 0 0.1978169 -0.9589288 0 0.2836471 -0.8939901 0 0.4480869 -0.8509002 0 0.5253273 -0.8011473 0 0.5984673 -0.7450736 0 0.6669822 -0.6832953 0 0.7301422 -0.6160277 0 0.7877245 -0.543979 0 0.8390988 -0.4678058 0 0.8838314 -0.3877455 0 0.9217666 -0.1323815 0 0.9911989 -0.04421025 0 0.9990223 0 -1 -1.95661e-7 0 -1 -7.96491e-7 0 -1 2.31276e-6 0 -1 4.00998e-7 0 -1 1.50691e-7 0 -1 7.82649e-7 0 -1 3.24601e-7 0 -1 1.37771e-5 0 -1 -1.37863e-5 0 -1 -3.24608e-7 0 -1 -2.78966e-6 0 -1 3.25489e-7 0 -1 -9.25206e-6 0 -1 2.69096e-7 0 -1 2.20705e-7 0 -1 -1.3208e-7 0 -1 -1.8695e-7 0 -1 0 0 -1 -7.92498e-7 0 -1 2.19553e-7 0 -1 4.53235e-7 0 -1 -4.63328e-7 0 -1 0 0 -1 6.95009e-7 0 -1 -4.3481e-7 0 -1 2.17406e-7 0 -1 6.5096e-7 0 -1 -9.06487e-7 0 -1 -4.39105e-7 0 -1 2.45183e-7 0 -1 -6.95492e-7 -1.30991e-6 -1 0 9.13606e-7 -1 0 0.6777479 0 0.7352944 0.6186746 0 0.7856473 0.5558266 0 0.8312984 0.4896169 0 0.8719378 0.4203996 0 0.9073392 0.4204195 0 0.9073299 0.4896354 0 0.8719273 0.5558433 0 0.8312872 0.6186447 0 0.7856709 0.09878647 0 0.9951087 0.09880131 0 0.9951072 0.9376831 0 -0.347492 0.9599232 0 -0.2802637 0.9773536 0 -0.2116128 0.9898775 0 -0.1419243 0.9898765 0 -0.1419317 0.9773548 0 -0.2116072 0.9599252 0 -0.2802565 0.9376862 0 -0.3474833 0 -1 -1.91175e-6 0 -1 5.92007e-7 0 -1 1.83707e-6 0 -1 1.27705e-6 0 -1 9.56123e-7 0 -1 1.27397e-6 0 -1 9.89887e-7 0 -1 2.54964e-6 0 -1 -8.87121e-7 0 -1 -2.07175e-6 -8.25579e-7 -1 -3.17332e-6 0 -1 -9.1693e-7 0 -1 -8.85549e-7 0 -1 -1.28191e-6 -7.63499e-7 -1 1.39731e-6 0 -1 -9.33417e-7 0 -1 -8.49843e-7 0 -1 -1.04231e-6 0 -1 1.8627e-6 0 -1 1.77482e-6 0 -1 9.19422e-7 0.7005713 0 -0.7135825 -0.7888107 0 -0.6146363 -0.8307239 0 -0.5566848 -0.8684415 0 -0.4957917 -0.9016444 0 -0.4324786 -0.9302668 0 -0.3668839 -0.9541258 0 -0.2994061 -0.9730872 0 -0.2304372 -0.9870733 0 -0.1602696 -0.9960075 0 -0.08926975 -0.9998413 0 -0.01781332 -0.9870746 0 -0.1602623 -0.9541217 0 -0.2994194 -0.9016483 0 -0.43247 -0.8684355 0 -0.4958023 -0.8307311 0 -0.556674 -0.7888111 0 -0.6146359 -0.7888109 0 -0.6146361 -0.830722 0 -0.5566874 -0.8684421 0 -0.4957908 -0.901643 0 -0.4324811 -0.9302641 0 -0.3668908 -0.9541254 0 -0.2994077 -0.9730874 0 -0.2304366 -0.9870736 0 -0.1602683 -0.9998413 0 -0.01781326 -0.9870744 0 -0.1602632 -0.9541224 0 -0.2994168 -0.9302684 0 -0.3668799 -0.901649 0 -0.4324686 -0.8684341 0 -0.4958045 -0.8307319 0 -0.5566727 -0.6884122 -3.17869e-4 0.7253197 -0.6883128 2.75342e-4 0.725414 -0.6883329 -1.21648e-4 0.7253949 -0.6884055 -7.42427e-5 0.7253261 -0.6883755 -1.13548e-5 0.7253546 -0.6883683 -9.1113e-5 0.7253614 -0.6883642 8.63165e-5 0.7253652 -0.6883819 0 0.7253484 -0.688384 0 0.7253465 -0.6884253 3.17833e-4 0.7253072 -0.6883304 4.4214e-5 0.7253974 -0.6883091 -5.6083e-5 0.7254176 -0.6883598 -4.42125e-5 0.7253694 -0.6884028 0 0.7253286 -0.6883779 0 0.7253523 -0.6883357 -2.71105e-4 0.7253924 -0.6883663 -3.44559e-5 0.7253633 -0.6883236 -9.71797e-5 0.7254038 -0.6883529 4.85988e-5 0.725376 -0.6885265 1.02715e-4 0.7252112 -0.6883837 -4.55594e-5 0.7253468 -0.6883276 1.21648e-4 0.7254 -0.6884155 -2.4044e-5 0.7253167 -0.6884558 4.55129e-5 0.7252783 -0.6883497 3.75901e-5 0.7253791 -0.6885163 -1.07863e-4 0.7252209 -0.6883289 -9.27003e-5 0.7253988 -0.6883654 8.09969e-5 0.7253641 -0.6882951 9.71825e-5 0.7254309 -0.6883383 0 0.7253898 -0.6884042 2.7479e-5 0.7253274 -0.6883935 0 0.7253374 -0.6883099 5.90358e-5 0.7254168 -0.6883555 1.03123e-4 0.7253736 -0.688496 -4.39412e-5 0.7252402 -0.6884025 9.41882e-6 0.725329 0.7933638 0 0.608748 0.793356 0 0.608758 0 1 -7.34262e-7 0 1 9.23293e-7 0 1 1.18121e-6 0 1 -1.86976e-6 0 1 -7.9489e-7 0 1 -7.39803e-7 0 1 8.05838e-7 0 1 6.23404e-7 0 1 -2.5929e-6 0 1 1.38489e-6 0 1 -4.26665e-7 0 1 -5.94629e-7 0 1 -3.43038e-6 0 1 -1.67651e-6 0 1 -8.06915e-7 0 1 1.38057e-6 0 -1 1.71519e-6 0 -1 -8.15054e-7 0 -1 -2.33162e-6 0 -1 2.37852e-6 0 -1 1.47961e-6 0 -1 4.17261e-7 0 -1 -1.72988e-6 0 -1 -9.94965e-7 0 -1 1.59331e-6 0 -1 2.60977e-6 0 -1 3.88935e-6 0 -1 -3.22335e-6 0 -1 -8.01667e-7 0 -1 -1.18121e-6 0 -1 1.25738e-6 0 -1 -3.69303e-6 0 -1 6.21869e-7 0.1421245 0 0.9898489 0.2601441 0 0.9655699 0.3742203 0 0.9273399 0.4833022 0 0.8754536 0.5849793 0 0.8110482 0.6783112 0 0.7347747 0.761789 0 0.6478253 0.8342334 0 0.5514116 0.894482 0 0.4471042 0.9417709 0 0.3362554 0.9753831 0 0.2205176 0.9948292 0 0.1015622 0.9998227 0 -0.0188322 0.9902921 0 -0.1390022 0.966389 0 -0.2570844 0.9284464 0 -0.3714666 0.8769524 0 -0.4805774 0.8128408 0 -0.582486 0.7368299 0 -0.6760782 0.7368484 0 -0.676058 0.8128682 0 -0.5824477 0.9284352 0 -0.3714946 0.9663916 0 -0.2570744 0.9902914 0 -0.1390078 0.9948306 0 0.1015499 0.975385 0 0.2205089 0.8944738 0 0.4471204 0.834221 0 0.5514302 0.761755 0 0.6478653 0.5850059 0 0.811029 0.3742204 0 0.9273399 0.2601063 0 0.9655801 0.1421244 0 0.9898488 0.999962 0 0.008727252 0.999962 0 0.008727371 -0.07845759 -3.65672e-5 -0.9969175 -0.07845276 -2.71853e-4 -0.9969179 -0.07849919 2.72705e-4 -0.9969142 -0.07832938 -3.34817e-4 -0.9969276 -0.07850849 0 -0.9969135 -0.07847714 2.83896e-5 -0.9969159 -0.07832932 -2.84441e-4 -0.9969276 -0.07862919 3.10726e-4 -0.996904 -0.07847994 -4.31315e-5 -0.9969157 -0.07852554 0 -0.9969121 -0.07861542 -3.10729e-4 -0.996905 -0.07845664 3.59673e-5 -0.9969176 -0.07844054 -7.7818e-6 -0.9969188 -0.07855695 2.31268e-6 -0.9969097 -0.07831573 1.57056e-4 -0.9969286 -0.07831412 3.3608e-4 -0.9969288 -0.07846838 2.6851e-5 -0.9969166 -0.07854604 -7.84952e-5 -0.9969105 -0.07830536 -1.56693e-4 -0.9969294 -0.07844209 7.78196e-6 -0.9969187 -0.07839471 -8.91058e-5 -0.9969225 -0.07856374 -7.28352e-5 -0.9969091 -0.07836562 2.84981e-4 -0.9969246 -0.07852077 0 -0.9969125 -0.07850456 4.10351e-6 -0.9969139 -0.07847803 7.80707e-5 -0.9969159 -0.07856386 7.24261e-5 -0.9969092 -0.07836979 1.39721e-5 -0.9969244 -0.07837009 8.87232e-5 -0.9969244 -0.07870763 -5.95068e-6 -0.9968978 -0.07854884 -2.67683e-6 -0.9969103 -0.07837492 -4.37713e-5 -0.9969241 -0.07849282 0 -0.9969147 -0.07849842 0 -0.9969143 -0.07846903 -2.72294e-5 -0.9969165 -0.07837599 4.35246e-5 -0.9969239 -0.07832503 -1.43306e-5 -0.996928 -0.7216398 -0.1013145 -0.6848149 -0.6921206 -0.2992727 -0.6568143 -0.6342235 -0.4853171 -0.6018539 -0.5503861 -0.6513714 -0.5222935 -0.4440023 -0.7907661 -0.4213683 -0.3194146 -0.8978292 -0.3031125 -0.1818228 -0.9680743 -0.1725478 -0.03675299 -0.9987156 -0.03487646 0.1098415 -0.988468 0.1042396 0.2519457 -0.9377416 0.2390899 0.3836933 -0.848641 0.3641263 0.4997641 -0.7247789 0.4742694 0.5953208 -0.5713315 0.5649544 0.6666029 -0.3944035 0.6325239 0.7115573 -0.194392 0.6752021 0.7197087 0.02325773 0.6938866 0.7105711 0.2011713 0.6742544 0.6665955 0.3943975 0.6325354 0.5953224 0.5713345 0.5649498 0.4997698 0.7247716 0.4742746 0.3836851 0.848648 0.3641186 0.2519412 0.9377455 0.2390796 0.1098415 0.988468 0.1042396 -0.0367375 0.9987167 -0.03486502 -0.1818349 0.9680702 -0.1725575 -0.3194161 0.8978271 -0.3031172 -0.4440045 0.79077 -0.4213583 -0.5503826 0.6513777 -0.5222895 -0.6342241 0.4853144 -0.6018552 -0.6921141 0.299274 -0.6568205 -0.7216399 0.1013153 -0.6848146 -0.7216326 0.1012921 -0.6848257 -0.6921169 0.2993107 -0.6568009 -0.6342293 0.4853055 -0.601857 -0.5503706 0.6513892 -0.5222877 -0.4439994 0.7907738 -0.4213566 -0.3194327 0.8978168 -0.30313 -0.1818396 0.9680692 -0.1725587 -0.03673809 0.9987167 -0.03486156 0.1098461 0.9884673 0.1042409 0.2519261 0.9377501 0.2390775 0.3837062 0.8486377 0.3641206 0.4997771 0.724763 0.47428 0.5954114 0.5712 0.5649919 0.6666034 0.3943817 0.6325371 0.7219434 0.1637384 0.6723001 0.7215115 -0.1637322 0.6727651 0.6665945 -0.3943948 0.6325381 0.5954161 -0.5711938 0.5649934 0.4997687 -0.7247728 0.4742738 0.3837144 -0.8486306 0.3641282 0.251932 -0.937748 0.2390794 0.1098398 -0.9884684 0.1042377 -0.03675168 -0.9987156 -0.0348792 -0.1818341 -0.968071 -0.172554 -0.3194251 -0.8978202 -0.3031281 -0.4440093 -0.7907718 -0.4213499 -0.5503789 -0.6513805 -0.5222898 -0.6342278 -0.4853043 -0.6018595 -0.6921084 -0.299319 -0.656806 -0.7216383 -0.1012901 -0.6848201 -0.6883449 -6.78352e-5 0.7253835 -0.6883494 -6.81534e-5 0.7253794 -0.688351 5.96324e-5 0.7253778 -0.6884295 2.22433e-4 0.7253033 -0.6883554 1.50831e-4 0.7253736 -0.6883496 7.48542e-5 0.7253791 -0.6884512 -2.10145e-4 0.7252827 -0.6880962 2.63437e-4 0.7256194 -0.6881805 -3.86197e-4 0.7255395 -0.6883482 -5.80293e-5 0.7253805 -0.688364 5.54275e-5 0.7253655 -0.6883577 -1.43837e-4 0.7253715 -0.6883636 5.80277e-5 0.7253659 -0.688439 -2.22422e-4 0.7252942 -0.6883557 -4.28273e-5 0.7253734 -0.6884523 2.24142e-4 0.7252817 -0.6883796 -1.69585e-4 0.7253507 -0.6883602 -5.63087e-5 0.7253691 -0.6881994 3.63454e-4 0.7255216 -0.6883448 -1.15208e-4 0.7253836 -0.6883481 1.12084e-4 0.7253807 -0.6883369 -1.44124e-5 0.7253912 -0.6883413 2.88238e-5 0.725387 -0.6883574 1.78304e-4 0.7253717 -0.6882472 -2.30469e-4 0.7254763 -0.6883578 3.51143e-5 0.7253713 -0.6883606 2.52297e-5 0.7253687 -0.6883847 1.33957e-4 0.7253458 -0.6883513 -1.73832e-4 0.7253775 0.9918061 -0.1011317 -0.07805913 0.9511899 -0.299391 -0.07485246 0.8716536 -0.4852987 -0.06859421 0.7564366 -0.6513527 -0.05952793 0.6102205 -0.7907751 -0.04802036 0.4390423 -0.8978018 -0.03455054 0.2498644 -0.9680811 -0.01966822 0.05051594 -0.9987154 -0.00397706 -0.1509658 -0.9884676 0.01188004 -0.3462349 -0.937752 0.02725005 -0.5273655 -0.8486241 0.04150587 -0.6868304 -0.7248048 0.05405539 -0.8182312 -0.5712714 0.06439524 -0.9161289 -0.3943459 0.07210689 -0.9841627 -0.1636497 0.06813758 -0.9841146 0.1636722 0.06877404 -0.91613 0.3943431 0.07210737 -0.8182268 0.5712777 0.06439512 -0.6868334 0.724802 0.0540558 -0.5273505 0.8486335 0.0415045 -0.3462327 0.9377529 0.02724999 -0.1509672 0.9884674 0.01188033 0.05049633 0.9987164 -0.003973901 0.2498739 0.9680787 -0.01966792 0.4390404 0.8978028 -0.03454995 0.6102226 0.7907734 -0.0480197 0.7564277 0.651363 -0.05952823 0.8716518 0.4853018 -0.06859409 0.951193 0.299381 -0.0748533 0.9918066 0.101126 -0.07805919 0.9918047 0.1011533 -0.07804775 0.9512015 0.2993539 -0.07485294 0.8716483 0.4853083 -0.06859439 0.7564226 0.6513692 -0.05952441 0.6102145 0.7907796 -0.04802125 0.4390309 0.8978074 -0.03455293 0.2498888 0.9680749 -0.01966571 0.0504924 0.9987165 -0.003974378 -0.1509742 0.9884663 0.0118826 -0.3462268 0.9377551 0.02724832 -0.5273296 0.8486465 0.04150283 -0.6868348 0.7248007 0.05405628 -0.8182449 0.5712509 0.06440401 -0.9161241 0.3943567 0.07210814 -0.9778819 0.1944816 0.07696676 -0.9959981 -0.02319234 0.08631372 -0.9765086 -0.2013049 0.07686066 -0.9161247 -0.3943551 0.07210898 -0.8182507 -0.5712425 0.06440508 -0.6868175 -0.7248172 0.05405533 -0.5273517 -0.8486327 0.04150497 -0.3462368 -0.9377514 0.0272485 -0.1509695 -0.988467 0.0118817 0.05051296 -0.9987155 -0.003976881 0.2498775 -0.9680777 -0.01966559 0.439027 -0.8978093 -0.03455221 0.6102178 -0.7907771 -0.04802012 0.7564294 -0.6513612 -0.05952554 0.8716458 -0.4853129 -0.06859499 0.9511974 -0.2993673 -0.0748524 0.9918044 -0.1011559 -0.07804793 -0.07873386 -7.3237e-4 -0.9968954 -0.07854205 6.12953e-6 -0.9969108 -0.07876574 -4.20175e-4 -0.9968931 -0.07847303 -1.6754e-4 -0.9969162 -0.0789197 4.20148e-4 -0.996881 -0.07821726 2.50269e-5 -0.9969365 -0.07835566 2.58719e-4 -0.9969254 -0.07844537 8.51926e-6 -0.9969184 -0.07843148 -8.51899e-6 -0.9969196 -0.07886344 7.3235e-4 -0.9968852 -0.07839959 1.40514e-4 -0.9969221 -0.07845288 2.89245e-5 -0.9969179 -0.07842642 -1.3961e-4 -0.9969199 -0.07846206 -7.00554e-6 -0.9969171 -0.07853233 1.22787e-4 -0.9969117 -0.07846397 1.97279e-5 -0.996917 -0.07845103 -3.32642e-5 -0.996918 -0.07845491 -1.97276e-5 -0.9969177 -0.07834124 -2.5872e-4 -0.9969267 -0.0784552 8.53547e-5 -0.9969177 -0.07845336 -8.51381e-5 -0.9969178 -0.07844346 -2.81538e-5 -0.9969186 -0.07847905 1.6842e-4 -0.9969158 -0.0784738 5.35276e-5 -0.9969162 -0.07830739 -2.7808e-5 -0.9969294 -0.07851445 -1.23144e-4 -0.996913 -0.07844996 3.35256e-5 -0.9969182 -0.07847326 -5.3801e-5 -0.9969162 0.08638352 0.2473618 0.9650648 0.08630716 0.3039821 0.9487602 0.08673763 -0.2642256 0.9605528 0.08659118 -0.2879629 0.9537187 0.08664613 -0.2627134 0.9609757 0.08602517 -0.2018146 0.9756385 0.08815062 -0.1380841 0.9864899 0.08687031 -0.1469271 0.9853253 0.08861529 -0.129756 0.9875783 0.08804184 -0.06949049 0.99369 0.08824384 -0.06722235 0.9938281 0.08659857 -0.01018923 0.9961912 0.08856469 0.03544938 0.9954395 0.08725607 0.05796247 0.9944983 0.08941966 0.09525191 0.9914289 0.08751553 0.123133 0.9885238 0.08713108 0.1508713 0.9847061 0.08782631 0.2073811 0.9743099 0.08658307 0.2086439 0.9741516 0.06944078 0.1818997 0.9808621 0.08649587 0.184503 0.9790185 0.08722364 0.1634353 0.9826907 0.08631753 0.1220936 0.9887581 0.08908271 0.03108394 0.9955391 0.08689677 -0.04250937 0.99531 0.08668547 -0.1058651 0.9905949 0.08716726 -0.2152916 0.9726518 0.08654242 0.316103 0.9447695 0.08749455 0.2688475 0.9592006 0.8660238 -0.4999789 0.00488615 0.8514939 -0.5243565 -0.002930581 0.9238706 -0.3826694 0.005220949 0.914594 -0.4043727 -8.62e-4 0.9659127 -0.2588226 0.004860401 0.9586771 -0.2844819 -0.002876877 0.9883294 -0.1523309 -6.44145e-4 0.9914327 -0.130514 0.005233943 0.9996184 -0.02749264 -0.002727508 0.9999867 0 0.005178749 0.9942814 0.1067875 -9.38901e-4 0.9914324 0.1305114 0.005342841 0.972513 0.2328303 -0.002931594 0.9659124 0.2588229 0.004899442 0.9238846 0.3826699 -0.001075267 0.9314099 0.3639111 0.00667268 0.8766663 0.4810879 -0.003258228 0.8660278 0.499983 0.003608167 -0.7456762 -0.6663061 -0.001805722 -0.7674506 -0.6410915 0.004637479 -0.5320298 -0.8467241 -0.001665174 -0.5694267 -0.8220177 0.006343841 -0.2768521 -0.9609098 -0.002330601 -0.3070374 -0.9516912 0.003453493 0 -0.9999918 0.004043638 0.3386303 -0.9408822 0.008391916 0.5320253 -0.846677 0.009342253 0.6683213 -0.7438213 -0.008751392 0.7456433 -0.6663324 0.004140734 0.2768375 -0.9609032 -0.005121946 0.05149787 -0.9986656 -0.003874838 0.7456593 0.666324 0.002169847 0.7299654 0.6834822 -0.001667141 0.5320481 0.8466989 0.005102872 0.4645425 0.8855364 -0.005059599 0.2768303 0.9608822 0.008392333 0.08549541 0.9962968 -0.009126245 0 0.999992 0.004037499 -0.3072304 0.9516289 0.003482818 -0.5714423 0.8206172 0.006421446 -0.772952 0.6344328 0.006358802 -0.7456765 0.6663069 -0.001361608 -0.5320231 0.8467266 -0.002365112 -0.2768594 0.9609076 -0.002340435 -0.8716255 0.4901601 0.003495395 -0.8660336 0.4999853 -7.45193e-4 -0.9238782 0.3826723 0.003340661 -0.9659099 0.2588173 0.005630552 -0.9736716 0.2279357 -0.002999603 -0.9914355 0.1305142 0.004672706 -0.9999825 0 0.005915284 -0.9993685 -0.03532385 -0.003859162 -0.9914333 -0.1305097 0.005212664 -0.9658723 -0.2588022 0.01059848 -0.9238665 -0.3826727 -0.005695164 -0.9334297 -0.3586974 0.006729185 -0.8660328 -0.4999819 -0.002359688 -0.8753346 -0.4834891 0.005265891 -0.9836669 -0.179808 -0.008273959 -0.9947069 0.1026997 -0.003322184 -0.9321271 0.3621138 -0.003579914 -6.56974e-5 0 1 -3.92305e-5 0 1 9.44397e-5 0 1 5.89048e-5 0 1 -5.76408e-5 0 1 1.761e-5 0 1 -4.53501e-5 0 1 -7.5334e-5 0 1 4.71152e-5 0 1 -1.71513e-4 0 1 -8.65614e-5 0 1 1.00083e-4 0 1 -1.16992e-4 0 1 3.39831e-5 0 1 2.88917e-5 0 1 1.85027e-5 0 1 2.96276e-5 0 1 2.85262e-5 0 1 -3.6903e-5 0 1 -3.39825e-5 0 1 1.50667e-5 0 1 6.20552e-5 0 1 6.4746e-5 0 1 3.99277e-5 0 1 2.96265e-5 0 1 -2.85263e-5 0 1 -5.24775e-5 0 1 3.84658e-5 0 1 -2.88928e-5 0 1 -5.83273e-5 0 1 5.83285e-5 0 1 -0.9827269 -0.1846356 0.01254945 -0.6865702 -0.727051 0.004274964 -0.1962593 -0.980552 0 0.2269637 -0.9738965 0.003640592 0.6778972 -0.7351319 -0.006045818 0.9212958 -0.3887735 0.008333444 0.9827265 0.1846377 0.01254916 0.6865643 0.7270566 0.004274487 0.1962593 0.980552 0 -0.2269637 0.9738965 0.003640711 -0.6778883 0.7351401 -0.006045639 -0.9212958 0.3887735 0.008333504 -0.9827269 0.1846356 -0.01254945 -0.6865705 0.7270507 -0.00427407 -0.1962633 0.9805513 0 0.2269637 0.9738965 -0.003640472 0.6779016 0.7351278 0.006045818 0.9212958 0.3887735 -0.008333384 0.9827265 -0.1846377 -0.01254916 0.6865763 -0.7270452 -0.004273951 0.1962601 -0.9805519 0 -0.2269639 -0.9738964 -0.003640651 -0.6778928 -0.735136 0.006045222 -0.9212958 -0.3887735 -0.008333504 8.5251e-5 0 1 1.613e-4 0 1 -1.70502e-4 0 1 -1.78876e-4 0 1 -0.9827269 -0.1846356 0.01254945 -0.6865643 -0.7270566 0.004274129 0.2269637 -0.9738965 0.003640472 0.6778928 -0.735136 -0.006045877 0.9212958 -0.3887735 0.008333384 0.9827265 0.1846377 0.01254916 0.6865763 0.7270452 0.004273951 0.1962601 0.9805519 0 -0.2269639 0.9738964 0.003640651 -0.6778972 0.7351319 -0.006045162 -0.9212936 0.3887787 0.008333623 -0.9827269 0.1846356 -0.01254945 -0.6865763 0.7270452 -0.004274964 0.2269672 0.9738956 -0.003640592 0.6778972 0.7351319 0.006045818 0.9212958 0.3887735 -0.008333444 0.9827265 -0.1846377 -0.01254916 0.6865705 -0.7270507 -0.004274487 0.1962633 -0.9805513 0 -0.2269672 -0.9738956 -0.003640711 -0.6779016 -0.7351278 0.00604552 -0.9212936 -0.3887787 -0.008333623 -1.27878e-4 0 1 2.23593e-5 0 1 1.613e-4 0 1 3.80851e-5 0 1 -2.55729e-5 0 1 4.26811e-5 0 1 0.05259364 -0.8040724 0.5922008 0.05445456 -0.8007231 0.5965545 0.05282735 -0.8034681 0.5929995 0.05243426 -0.8048439 0.591166 1.6719e-5 -0.7983743 0.6021616 0.002024233 -0.8003352 0.5995494 -0.001269161 -0.2487798 0.9685592 -0.002925813 -0.2538338 0.9672435 -0.007962524 -0.1658957 0.9861112 0.002552807 -0.2004575 0.9796992 -0.003658592 -0.1782385 0.9839805 0.003050029 -0.2002782 0.9797344 0.01807415 -0.1979932 0.9800369 -0.01164174 -0.09681355 0.9952345 -0.001932024 -0.124163 0.99226 1.29088e-4 -0.1494485 0.9887695 -0.004974305 -0.04625815 0.9989172 -0.002964854 -0.04967993 0.9987608 8.52e-4 -0.008641302 0.9999623 -0.005750656 0.01754164 0.9998297 -0.002423584 0.02505058 0.9996833 0.002532541 0.08461862 0.9964102 -0.0138846 0.06269323 0.9979363 -0.001871347 0.09229874 0.9957296 0.002093434 0.1513783 0.9884737 -0.01034587 0.1313104 0.9912873 -0.003987252 0.1507167 0.988569 -0.002005159 0.1594815 0.987199 -8.58641e-4 0.1670507 0.985948 0.001540362 0.1914911 0.9814932 -7.84193e-4 0.1930963 0.9811795 -0.002315223 0.2173998 0.9760799 -0.003112971 0.2872215 0.9578592 -0.00152862 0.2825316 0.9592568 0.002498328 0.2453842 0.9694228 0.00317794 -0.1166508 0.9931679 -4.20436e-4 -0.1830814 0.9830977 0.002309441 0.8107383 0.5854043 4.20603e-5 0.8086404 0.5883033 0.05222123 0.8109965 0.5827159 0.05243355 0.8156015 0.5762335 0.04952996 0.8163449 0.5754371 0.05311322 0.8161113 0.5754491 0.173646 0.9848082 0 0.707108 1.20886e-5 -0.7071056 0.7070942 -3.83837e-5 -0.7071195 0.7071092 0 -0.7071044 0.7070609 -9.14581e-5 -0.7071527 0.7071056 7.05617e-5 -0.707108 0.7070993 0 0.7071143 0.7071051 2.38786e-5 0.7071086 0.7071105 0 0.7071031 0.2992727 0.3018983 0.9051482 0.3055717 0.3166177 0.8979863 0.2988337 0.2005608 0.9329919 0.3065554 0.3754072 0.8746961 0.3012621 0.3197711 0.8983249 0.3003623 0.2698797 0.9148483 0.3012842 0.2410517 0.9225627 0.3009507 0.2379667 0.9234721 0.302789 0.2488151 0.9200054 0.3019041 0.2452253 0.9212592 0.3030655 0.2495177 0.9197239 0.2958714 0.2588932 0.9194751 0.2970788 0.3134166 0.9019503 -0.7070924 0 -0.7071212 -0.7071095 -2.17204e-4 -0.707104 -0.7070913 0 -0.7071223 -0.1736255 0.9848117 1.2274e-5 -0.1737297 0.9847934 -6.97879e-5 -0.1756692 0.9844478 -0.001746654 -0.1733962 0.9848522 1.09201e-4 -0.7071096 -2.21683e-5 0.707104 -0.7070975 0 0.7071161 -0.7071057 6.32001e-5 0.707108 -0.707091 0 0.7071226 0.1735859 0.9848188 -6.35804e-5 0.173495 0.9848347 7.05643e-5 0.1736968 0.9847993 0 0.1735046 0.9848331 1.51007e-4 -0.1732081 0.9848853 -6.50447e-5 -0.1736466 0.984808 -9.87374e-7 -0.1742536 0.9847007 3.08129e-4 -0.1736379 0.9848096 -2.36109e-6 -0.173456 0.9848417 3.46252e-7 -0.1735071 0.9848326 -1.44935e-4 -3.73308e-7 -1 0 -6.66001e-7 1 0 -2.35851e-4 1 -2.35034e-4 0 1 0 -5.02181e-7 1 -2.00913e-5 -0.7071087 0 0.7071049 -0.7071062 4.12215e-5 0.7071074 -0.7071132 0 0.7071005 0.7071058 5.15269e-5 0.7071078 0.7071061 0 0.7071075 0.707109 0 0.7071046 0.7071062 0 -0.7071075 0.7071068 0 -0.7071068 -0.7071074 0 -0.7071062 -0.7071068 0 -0.7071068 0.2994471 0.5034906 -0.8104498 0.2994216 0.4369302 -0.8481974 0.3015149 0.4594175 -0.8354787 0.3002054 0.3641705 -0.8816216 0.3012828 0.3745344 -0.8768995 0.3009626 0.2915903 -0.9079629 0.3007037 0.2894982 -0.9087179 0.3000558 0.2167198 -0.9289774 0.3000515 0.1413053 -0.9433991 0.2993806 0.06399101 -0.9519856 0.2985677 -0.02094262 -0.9541587 0.2935732 0.6082994 -0.737419 0.3009482 0.5197826 -0.799535 0.3008559 -0.1033433 -0.9480537 0.3013069 -0.0585944 -0.9517252 0.301568 -0.06014233 -0.951546 0.304197 0.5346192 -0.7884456 0.301532 0.02448266 -0.9531417 0.3018213 0.1178564 -0.9460517 0.3016816 0.1990551 -0.9323976 7.31248e-5 1 3.47475e-4 0 1 0 0.1521026 0.5140742 -0.8441521 0.152096 0.5140361 -0.8441764 0.1521216 0.5140693 -0.8441517 0.152101 0.5140843 -0.8441462 0.1242415 0.008188247 -0.9922183 0.1349002 4.37901e-4 -0.9908591 0.1218684 0 -0.9925463 0.9932414 0.003403007 -0.1160173 0.9939942 0.006466567 -0.1092417 0.9510689 -0.002320349 -0.3089706 0.9586398 0.005219519 -0.2845746 0.882927 -0.001936495 -0.4695065 0.8952636 0.004676163 -0.4455124 0.787995 -0.001712501 -0.6156793 0.8049644 0.004414141 -0.5933068 0.6691526 -0.001608967 -0.7431232 0.68373 0.002405941 -0.7297312 0.5130046 0.002411782 -0.8583825 0.3421382 0.004638016 -0.9396382 0.3536238 0.001656293 -0.9353863 0.5298433 -0.001616954 -0.8480942 0.4889768 0.5938253 -0.6389628 0.4889535 0.5938206 -0.6389849 0.4889607 0.5937643 -0.6390317 0.4889923 0.5937892 -0.6389843 0.4889196 0.5938299 -0.6390022 0.4889473 0.5937779 -0.6390293 0.4890123 0.5934789 -0.6392573 0.4893463 0.5933848 -0.6390891 0.4893357 0.5932657 -0.6392077 0.4889543 0.5934355 -0.639342 0.4889358 0.5938122 -0.6390062 0.9942751 0 0.1068506 0.9942708 3.96259e-4 0.1068908 0 1 4.03523e-7 0 1 8.64484e-7 0 1 -1.10684e-6 5.56875e-5 1 8.34433e-5 -4.06746e-5 1 -1.95285e-5 0 1 -1.21553e-6 4.32652e-6 1 -2.0971e-6 0 1 -5.29643e-7 -9.62576e-6 1 -5.42315e-5 0 1 -6.60118e-6 3.64969e-6 0 -1 6.60291e-6 0 -1 0 0 -1 0.2419169 0 -0.970297 0.2420626 -5.65054e-5 -0.9702607 0.2419444 0 -0.9702901 0.01921916 -0.1964674 -0.9803221 0.01945793 -0.1962846 -0.9803539 0.01914417 -0.1963562 -0.9803458 0.01948148 -0.1964796 -0.9803144 -0.09768426 -0.06762021 -0.9929176 -0.09793037 -0.06772077 -0.9928865 -0.1139335 -0.07059299 -0.9909772 0.247544 -0.431774 -0.8673483 0.2477962 -0.4318858 -0.8672206 0.2478057 -0.431844 -0.8672389 0.2478229 -0.4318477 -0.8672321 -0.002770125 -0.7938166 -0.6081508 0.002768516 -0.7930908 -0.6090971 0.002393543 -0.8023675 -0.5968256 0.08844619 -0.9776614 -0.190671 0.0876671 -0.9779536 -0.1895294 0.5617681 -0.7058363 -0.4315226 0.5598606 -0.7069695 -0.4321462 0.857157 -2.59148e-5 -0.5150552 0.8572009 3.13349e-4 -0.5149821 0.8571677 0 -0.5150375 0.8572716 1.11991e-4 -0.5148645 0.8571525 0 -0.5150628 0.6704319 -0.738333 0.07338595 0.6711855 -0.7378204 0.07163178 0.005099356 -0.9999685 -0.006090402 0.005274891 -0.9999663 -0.006294071 -0.2596211 -0.8112684 -0.5238707 -0.260433 -0.8108544 -0.5241086 -0.2614247 -0.8094305 -0.5258132 -0.1330901 -0.9497874 0.2831798 -0.1383726 -0.9466589 0.2910156 0.6203015 -0.6054911 0.4986048 0.6293815 -0.6068264 0.4854285 0.6202605 -0.6052715 0.4989222 -0.2614223 -0.7844794 0.5623615 -0.2657262 -0.7781764 0.5690616 0.5441459 -0.491479 0.679966 0.5519136 -0.5220034 0.6503106 0.9563039 -5.33005e-6 0.2923745 0.9563073 -7.21088e-6 0.2923636 0.9563045 0 0.2923725 0.9563091 0 0.2923576 0.9563084 6.96947e-6 0.29236 0.9563001 0 0.292387 0.9563033 0 0.2923767 -0.3143249 -0.6694015 0.6731281 -0.3133058 -0.6739043 0.6690983 0.5823953 -0.5481665 0.6002743 0.5833407 -0.5326942 0.613148 -0.4895007 -0.7737874 -0.4020474 -0.4769584 -0.7828338 -0.3996024 -0.4905779 -0.7717437 -0.4046543 -0.4895384 -0.7717654 -0.4058696 -0.2599804 -0.7879205 0.5582039 -0.2606278 -0.7888812 0.5565427 -0.2571085 -0.7941617 0.5506383 -0.1976335 -0.8818942 0.4280229 -0.3415379 -0.8074122 -0.4810796 -0.3396709 -0.8093878 -0.4790775 -0.3404459 -0.8089286 -0.479303 -0.339659 -0.8058018 -0.485093 -0.1583195 -0.9271802 0.3395171 -0.158303 -0.9271917 0.3394935 -0.1652374 -0.9227669 0.3481349 0.6201958 -0.6053452 0.4989132 0.6201653 -0.6053543 0.4989401 0.6201658 -0.6053954 0.4988896 0.6232984 -0.5958915 0.506372 0.6202033 -0.6053272 0.4989258 0.7313343 6.15767e-6 -0.6820192 0.7313409 0 -0.6820122 0.7313587 -3.4117e-6 -0.681993 0.7313656 5.37579e-6 -0.6819857 0.7313165 -7.07347e-5 -0.6820383 0.731341 0 -0.682012 0.7313444 0 -0.6820084 0.6716748 -0.7237838 0.1580824 0.6717023 -0.7237567 0.1580895 0.5967881 -0.7281837 -0.3370351 0.5967862 -0.7282003 -0.3370025 0.596779 -0.7281879 -0.3370422 0.5968129 -0.7281653 -0.3370307 -0.489531 -0.7737845 -0.4020161 -0.4895565 -0.7737663 -0.4020203 -0.4894989 -0.7737814 -0.4020614 -0.173702 3.6716e-5 -0.9847983 -0.1737984 8.90361e-6 -0.9847813 -0.1737598 1.80539e-5 -0.9847881 -0.173654 -2.53229e-6 -0.9848068 -0.1747893 0.002078711 -0.9846037 -0.1702913 0 -0.9853939 -0.1736993 1.40023e-5 -0.9847988 -0.1736413 2.00427e-5 -0.984809 -0.1736326 0 -0.9848105 -0.1736169 3.88495e-5 -0.9848133 -0.173646 0.003083109 -0.9848034 -0.06389439 -0.8039118 -0.5913065 -0.06391143 -0.8039116 -0.5913048 -0.06387138 -0.8039408 -0.5912697 0.2660147 -0.7118194 -0.6500381 0.1125411 -0.2950709 -0.9488244 0.1124847 -0.2951809 -0.9487968 0.7312242 -1.26853e-4 -0.6821373 0.7313297 -1.51368e-4 -0.6820241 0.1294807 0.6469482 -0.7514604 0.1311559 0.636482 -0.7600585 0.1297865 0.5670983 -0.8133603 0.1312261 0.5570745 -0.820029 0.1300992 0.4751022 -0.8702598 0.1309028 0.482141 -0.866259 0.1303598 0.3899282 -0.9115714 0.130653 0.3924956 -0.9104268 0.1306354 0.2985061 -0.945425 0.1303806 0.3008572 -0.9447147 0.1308649 0.201766 -0.9706518 0.1310163 0.1030126 -0.9860138 0.1314092 0.001798987 -0.9913267 0.1326755 0.7186206 -0.6826285 0.1308833 0.6952005 -0.7067998 0.1335844 0.7839136 -0.6063291 0.1298397 0.7442646 -0.6551427 0.1326431 0.8402605 -0.5257073 0.1337348 0.8416865 -0.5231433 0.1298232 0.8028379 -0.5818912 0.1307551 0.8735569 -0.4688299 0.1406669 -0.7828235 -0.6061357 0.1354517 -0.7157037 -0.6851432 0.1329452 -0.6432014 -0.7540673 0.1271935 -0.7071854 -0.6954932 0.1367278 -0.6007337 -0.7876704 0.1268587 -0.5683307 -0.8129621 0.1319851 -0.6386305 -0.7581102 0.1195711 -0.6545718 -0.7464842 0.1287612 -0.4868472 -0.8639447 0.1313906 -0.4811668 -0.8667266 0.1287639 -0.5391659 -0.8322979 0.1304069 -0.3167673 -0.9394959 0.1310355 -0.3865419 -0.9129157 0.1327891 -0.2938224 -0.9465915 0.129952 -0.2273248 -0.9651094 0.1328023 -0.1964181 -0.9714853 0.1299234 -0.1352473 -0.9822566 0.1306042 -0.05704742 -0.989792 0.1298773 -0.05860859 -0.9897964 0.1325044 -0.09682339 -0.9864421 0.1314096 -0.3838073 -0.914015 0.1319834 -0.4769492 -0.8689649 0.1294752 0.02542275 -0.9912567 0.1297096 0.1174724 -0.9845688 0.1301538 0.2090942 -0.9691954 0.02614343 0.8483794 -0.5287428 0.02615278 0.8485465 -0.5284742 0.02613884 0.7906676 -0.6116876 0.02614277 0.7907961 -0.6115212 0.02611088 0.7240328 -0.6892712 0.02614384 0.7250093 -0.6882428 0.02613568 0.6512956 -0.758374 0.02615189 0.6518538 -0.7578937 0.02614057 0.5719133 -0.8198976 0.02614492 0.5720733 -0.8197857 0.02614349 0.4862855 -0.8734089 0.02614152 0.4862704 -0.8734173 0.02614265 0.3956836 -0.9180147 0.02614748 0.3957735 -0.9179759 0.02614593 0.3009592 -0.9532786 0.02614533 0.3010112 -0.9532622 0.02614599 0.2032467 -0.9787784 0.02614295 0.203341 -0.9787589 0.02614504 0.1034619 -0.9942898 0.02614158 0.1036414 -0.9942712 0.02614891 0.002579748 -0.9996548 0.02614587 -0.09850412 -0.9947932 0.02614569 -0.1982902 -0.9797946 0.0261473 -0.2962321 -0.9547581 0.02614623 -0.3910832 -0.9199839 0.02607995 -0.4820291 -0.8757669 0.02613121 -0.5704233 -0.8209353 0.02620023 -0.5678721 -0.8226998 0.02613729 -0.6482968 -0.760939 0.02614581 -0.6480162 -0.7611778 0.02614957 -0.7214842 -0.691937 0.0261451 -0.7216272 -0.6917881 0.02601307 -0.7910329 -0.6112205 0.02614176 -0.7877014 -0.6155024 0.02369952 -0.996974 -0.07403492 0.02584266 -0.9851169 -0.1699322 0.03041094 -0.9871399 -0.1569395 0.02576255 -0.9632396 -0.2674056 0.02718949 -0.9663418 -0.2558208 0.02698689 -0.9355898 -0.3520562 0.02625399 -0.8896421 -0.4559033 0.02654105 -0.8952969 -0.4446789 0.0260601 -0.8458589 -0.5327698 0.0264073 -0.8528169 -0.5215419 0.02616977 0.8833994 -0.4678896 0.0256353 0.9247737 -0.379653 0.02565956 0.9605695 -0.2768536 0.02539265 0.9852094 -0.1694629 0.02302432 0.9970237 -0.07357805 0.02963131 0.9879413 -0.1519671 0.02759516 0.9676026 -0.2509656 0.02670747 0.9373649 -0.3473239 0.0264973 0.8974773 -0.440264 0.02583974 -0.9260998 -0.3763927 0.02611714 -0.4832913 -0.87507 0.02613008 -0.3903926 -0.9202777 0.02613943 -0.295946 -0.954847 0.02613496 -0.1979141 -0.9798709 0.02610111 -0.09662526 -0.9949786 0.02613681 0.003204107 -0.9996533 -1 0 0 -0.9999999 -5.40979e-4 3.20494e-4 -1 -2.31911e-4 5.35224e-5 -1 0 1.06574e-5 -0.9999999 1.8607e-4 -4.87157e-4 -1 -7.53628e-5 1.78092e-5 -1 0 1.38542e-5 -1 0 2.32579e-5 -1 0 3.16362e-5 -1 0 2.29269e-5 -1 0 5.00629e-5 -1 -2.33004e-4 1.1791e-5 -1 -2.52857e-4 4.69511e-5 -1 0 3.42448e-5 -1 -1.73659e-5 3.51017e-6 -1 -4.03356e-5 1.00744e-4 -1 0 2.92113e-5 -1 0 5.80953e-5 -1 0 3.98255e-5 -1 0 2.96397e-5 -1 0 2.86352e-5 -0.9999994 -0.001118421 -1.58735e-5 -1 0 4.30517e-5 -1 -1.17069e-4 1.10263e-4 -1 0 1.85113e-5 -1 0 6.83581e-5 -1 0 4.81251e-6 -1 -2.08385e-5 0 -1 -3.34941e-5 8.94996e-6 -1 -1.17058e-4 -2.93741e-4 -1 -1.59783e-4 4.7842e-5 -1 2.28519e-5 5.92681e-5 -1 0 1.59043e-5 -1 0 6.3885e-5 -1 5.41555e-5 1.97417e-5 -1 4.37101e-5 0 -1 2.35336e-4 2.65514e-5 -0.9999997 7.68069e-4 2.6754e-4 -1 -3.62766e-5 7.88684e-5 -1 0 5.882e-5 -1 2.09925e-5 0 -1 0 5.16184e-5 -1 4.00064e-5 9.53281e-5 -1 -3.66354e-5 1.06409e-5 -1 1.589e-4 2.7648e-5 -1 0 5.38457e-5 -1 0 4.55096e-5 -1 -9.10291e-5 9.71792e-6 -1 -1.88793e-5 3.34128e-5 -1 0 1.43864e-5 -1 1.08862e-4 1.07591e-4 -0.9999983 0.00186181 2.54516e-6 -0.2588278 -0.9659236 0 -0.2588171 -0.9659264 2.24104e-5 -0.2588083 -0.9659287 8.21259e-6 -0.2588167 -0.9659265 7.05319e-6 -0.2588395 -0.9659204 3.99987e-6 -0.258816 -0.9659267 1.14688e-5 -0.2578724 -0.966179 -2.44801e-4 -0.2588269 -0.9659238 -3.94586e-6 -0.2588227 -0.9659245 -8.81567e-4 -0.2588291 -0.9659231 2.65866e-7 -0.2587788 -0.9659366 1.33698e-5 -0.2588349 -0.9659217 -4.53091e-6 -0.2587902 -0.9659336 1.73789e-5 -0.2595198 -0.9657378 -2.90029e-4 -0.2600937 -0.9655834 4.15137e-4 -0.2587376 -0.9659445 0.002476036 -0.2585592 -0.9659954 6.60874e-6 -0.2585127 -0.9660072 -0.001196801 -0.004369258 0.9999905 5.5315e-5 0.005310356 0.9999859 3.50766e-4 0.6642865 0 -0.7474781 0.7225833 0 -0.691284 0.7762804 0 -0.6303878 0.8247651 0 -0.5654757 0.8678229 0 -0.4968737 0.9052528 0 -0.4248734 0.9366811 0 -0.3501836 0.9619695 0 -0.2731569 0.9809332 0 -0.1943458 0.993452 0 -0.1142508 0.9994417 0 -0.03341156 0.9988644 0 0.04764646 0.9917242 0 0.1283867 0.9780603 0 0.2083225 0.9579764 0 0.2868472 0.9315978 0 0.3634906 0.8990976 0 0.4377481 0.860718 0 0.5090821 0.8165864 0 0.5772233 0.7671888 0 0.6414215 0.7127365 0 0.701432 0.6535339 0 0.7568973 0.5901222 0.002023994 0.8073115 -0.99561 0 0.09359943 -0.99992 0 0.01265782 -0.9976593 0 -0.06838178 -0.988842 0.0011819 -0.1489639 0.4048157 -0.01355725 -0.9142979 0.4140057 0.009674727 -0.910223 0.4645448 -0.01977121 -0.885329 0.4869028 0.01860105 -0.8732581 0.5348306 -0.01354718 -0.8448508 0.581902 -0.01564782 -0.8131084 0.6014645 0.01603543 -0.7987387 0.5118111 -0.005083322 0.8590831 0.4519219 -0.01350057 0.8919553 0.3782482 -0.008932411 0.9256613 0.4057152 0.01100081 0.9139334 0.3020001 -0.008073329 0.9532737 0.3143435 0.006148993 0.9492894 0.2238939 -0.008562505 0.9745759 0.1440692 -0.02423876 0.9892708 0.06353831 -0.02224403 0.9977316 0.08622378 0.02030366 0.9960689 -0.004430949 0.009434401 0.9999457 -0.01748383 -0.03248083 0.9993194 -0.09245049 0.02361923 0.9954372 -0.1787512 0 0.9838944 -0.2577552 0 0.9662104 -0.3352638 0 0.9421243 -0.4104827 0 0.9118685 -0.4829332 0 0.8756572 -0.5544324 0 0.8322288 -0.6178678 -0.02063965 0.786011 -0.6792964 -0.03193485 0.7331689 -0.7169938 0.02485054 0.6966365 -0.7367876 -0.009755611 0.6760539 -0.789137 -0.008940398 0.6141522 -0.8362698 -0.009807348 0.5482304 -0.8779266 -0.01328319 0.478611 -0.9042646 0.01100695 0.4268307 -0.913844 -0.005670607 0.4060258 -0.9437364 -0.005452394 0.3306538 -0.9674118 -0.006852269 0.253116 -0.9847456 -0.004530072 0.1739415 -0.9709199 -0.003181576 -0.2393836 -0.951747 -0.01251608 -0.3066288 -0.9238229 -0.007485628 -0.3827472 -0.9347815 0.01031386 -0.3550738 -0.8965865 0.003091871 -0.4428579 -0.8599748 0.006680965 -0.510293 -0.8898072 -0.006276249 -0.4562936 -0.9735041 0.007175743 -0.2285569 -0.986172 0 0.1657248 -0.9718378 0.002323865 0.2356398 -0.9481641 0.004553556 0.3177487 -0.8504264 0.009572803 0.5260069 -0.7969349 0.006802201 0.6040269 -0.6275865 0.02370345 0.778186 -0.5522603 0.01121836 0.8335963 -0.4829095 0 0.8756703 -0.4104569 0 0.91188 -0.1787212 0 0.9838998 -0.09841817 0 0.9951452 0.1995688 0.01841604 0.9797108 0.5228189 0.007814049 0.8524079 -0.9885886 0 -0.1506407 -0.9976591 0 -0.06838458 -0.9999199 0 0.01265811 -0.9956103 0 0.09359562 0.5878576 0 0.8089644 0.6535223 0 0.7569073 0.7671719 0 0.6414416 0.8165796 0 0.5772329 0.8607074 0 0.5091 0.8990937 0 0.4377562 0.9315952 0 0.3634976 0.9579764 0 0.2868474 0.9917249 0 0.1283816 0.9988643 0 0.0476455 0.9994417 0 -0.03341156 0.993452 0 -0.1142509 0.9809332 0 -0.1943456 0.9052603 0 -0.4248577 0.8678331 0 -0.496856 0.8247521 0 -0.5654945 0.776264 0 -0.630408 0.7225834 0 -0.6912838 0.6546155 0.008365631 -0.7559158 0.1736633 -0.9848051 -4.60928e-6 0.1736566 -0.9848063 -3.36346e-5 0.1736538 -0.9848068 7.06343e-7 0.1736513 -0.9848073 1.48098e-6 0.1711681 -0.9852408 -0.001499533 0.1729523 -0.98493 6.02322e-4 0.171655 -0.9851571 3.24033e-4 0.1736308 -0.9848109 -3.45737e-5 -0.2301394 -0.8387174 0.4935474 -0.2301753 -0.8386877 0.4935812 -0.2301838 -0.8387126 0.493535 -0.2301406 -0.8386325 0.4936912 -0.2301912 -0.8386219 0.4936856 -0.2301726 -0.8386491 0.4936479 -0.2323758 -0.8371163 0.495215 -0.2302294 -0.8386599 0.4936033 -0.2301921 -0.838622 0.4936851 -0.2302007 -0.8385634 0.4937804 -0.2302088 -0.8386334 0.4936578 -0.2300829 -0.838787 0.4934555 -0.2305506 -0.8375551 0.4953261 -2.51955e-5 -1 9.47891e-5 3.06062e-6 -1 2.79643e-5 -6.51382e-5 -1 1.74484e-4 1.23554e-6 -1 0 -8.01388e-4 -0.9999992 0.001031756 -1.29881e-5 -1 7.04939e-5 2.17667e-4 -0.9999998 5.6223e-4 8.39868e-7 -1 0 -3.06338e-7 -1 0 0.2930566 -0.549168 -0.7826445 0.2960852 -0.4232531 -0.8562655 0.3002288 -0.4554895 -0.8380884 0.3079434 -0.4513505 -0.8375284 0.3009373 -0.4177392 -0.857281 0.1325659 -0.5593701 -0.8182491 0.6091676 0.3014442 -0.7335164 0.6079616 0.2821163 -0.7421544 0.6091365 0.2420043 -0.7552396 0.608175 0.229003 -0.7600532 0.6089669 0.1803417 -0.7724223 0.608439 0.1742021 -0.7742453 0.6086256 0.1185471 -0.7845518 0.6087194 0.11754 -0.7846306 0.6083623 0.06228381 -0.7912117 0.6081503 0.005830585 -0.7938006 0.6075513 -0.3683537 -0.7037023 0.6095987 -0.3224903 -0.7241474 0.6099553 -0.3323044 -0.7193944 0.6086844 0.3141555 -0.7285669 0.6092177 0.3632644 -0.7049062 0.6084729 0.3704466 -0.7018049 0.6089693 0.4157491 -0.6755065 0.6086689 -0.06462174 -0.7907884 0.608166 -0.03794187 -0.7929027 0.6088739 -0.1164999 -0.7846658 0.6088485 -0.1719645 -0.7744235 0.6061242 -0.2221752 -0.7637093 0.6070076 -0.2197526 -0.7637085 0.6080018 -0.2516974 -0.7529822 0.6055719 -0.2754662 -0.746593 0.60706 -0.2796593 -0.7438205 0.6099712 -0.3096431 -0.7294219 0.6059112 -0.1614686 -0.7789734 0.6063449 -0.1058672 -0.7881232 0.606491 -0.04998326 -0.7935177 0.6094824 -0.01397937 -0.7926765 0.6089977 0.05429321 -0.7913117 0.2741436 0.3408696 -0.8992515 0.2758265 0.3341931 -0.9012408 0.2747393 0.276759 -0.9208272 0.2768443 0.2678408 -0.9228318 0.2753171 0.2107566 -0.937967 0.2762728 0.2063893 -0.9386569 0.2758129 0.1436391 -0.9504184 0.2762024 0.07577341 -0.9581078 0.2764378 0.00778383 -0.9610003 0.2767435 -0.06002545 -0.9590672 0.277978 -0.1091113 -0.9543705 0.2782338 -0.1764305 -0.9441707 0.2733276 -0.231253 -0.9337098 0.272746 -0.2996129 -0.9142438 0.2767578 -0.2646024 -0.9237915 0.2784723 -0.3341382 -0.9004471 0.2766065 0.3895624 -0.8784816 0.2726944 -0.1960577 -0.9419125 0.2732845 -0.1274058 -0.9534587 0.2742514 -0.04455006 -0.9606257 0.2746961 0.01817202 -0.9613594 0.2751861 0.08129584 -0.9579477 0.2757142 0.1441425 -0.9503709 -0.002103269 0.360174 -0.9328827 -0.002771437 0.3000755 -0.9539116 -0.004279077 0.2295128 -0.9732963 -0.009802579 0.1146593 -0.9933565 -0.009766876 -0.01388061 -0.9998561 0.002557754 -0.1152015 -0.993339 -0.009375274 -0.1421718 -0.9897976 0.00440222 -0.1787943 -0.9838767 0.00243026 -0.2414148 -0.970419 -0.004530072 -0.2568124 -0.9664508 0.004405021 -0.3107695 -0.9504751 -0.002522826 -0.3270958 -0.9449878 0.003956735 -0.04733407 -0.9988714 0.003631889 0.01936131 -0.999806 0.002883732 0.08497524 -0.996379 0.004139542 0.1503281 -0.9886276 0.002312064 0.2150312 -0.9766045 0.003191053 0.2789272 -0.960307 0.003732919 0.3465721 -0.9380159 -0.5011221 -0.03882569 0.8645052 -0.5012786 -0.177217 0.8469439 -0.4996038 -0.2677286 0.8238431 -0.5008521 -0.4101632 0.7621768 -0.5008702 -0.539672 0.6766708 -0.4982181 -0.5992033 0.6266852 -0.5012555 -0.6412851 0.5809443 -0.4996084 -0.7008308 0.5091441 -0.5016332 -0.777984 0.3782925 -0.4976319 -0.8120691 0.3048056 -0.5011233 -0.8341916 0.230217 -0.4984973 -0.8529617 0.1547793 -0.4981957 -0.8635739 0.0777269 -0.5006014 -0.8656781 0 -0.5015916 -0.8520869 -0.1495124 -0.5014375 -0.815941 -0.2877511 -0.4996297 -0.7804707 -0.3758133 -0.4982333 -0.7442888 -0.4447447 -0.5012648 -0.7090776 -0.495926 -0.4996347 -0.6523162 -0.569955 -0.5012657 -0.5515459 -0.6667308 -0.4996261 -0.477164 -0.7229719 -0.5008576 -0.3401451 -0.7958914 -0.5008607 -0.1926668 -0.8438116 -0.4996184 -0.1162091 -0.8584154 -0.5012601 0.02330255 -0.864983 -0.4996163 0.1162093 -0.8584167 -0.5008637 0.2675035 -0.8231509 -0.501264 0.396216 -0.7692512 -0.4996123 0.4771677 -0.722979 -0.4982281 0.5406223 -0.6778616 -0.5012644 0.5866379 -0.636074 -0.4996169 0.6523236 -0.5699622 -0.5008543 0.742992 -0.4439684 -0.5008612 0.8103269 -0.3041518 -0.4982229 0.8358043 -0.2306625 -0.5016286 0.8505833 -0.1577242 -0.4976316 0.8638963 -0.07775747 -0.5011188 0.8653786 0 -0.4983548 0.8634826 0.07772022 -0.5009776 0.8570439 0.1204051 -0.4984638 0.8529804 0.1547847 -0.5007196 0.833728 0.2327607 -0.5011031 0.7797037 0.375444 -0.4982244 0.7442931 0.4447473 -0.501266 0.7090732 0.4959312 -0.4996259 0.65232 0.5699584 -0.5016203 0.5419349 0.6743023 -0.501113 0.410101 0.7620386 -0.5008403 0.2675125 0.8231623 -0.4982339 0.1930041 0.8452885 -0.5016493 0.1194761 0.856781 -0.4976135 0.03891646 0.8665254 -0.5011184 0.1160942 0.8575562 -0.5015759 0.2625359 0.8243158 -0.4979686 0.3407955 0.7974244 -0.5019093 0.4052729 0.7640948 -0.4976132 0.4778022 0.7239381 -0.5011356 0.5395749 0.6765517 -0.4982236 0.5992 0.626684 -0.5012598 0.6412817 0.5809446 -0.4996062 0.7008318 0.5091448 -0.5016378 0.7779814 0.3782915 -0.4976353 0.8120669 0.3048059 -0.5011313 0.8341869 0.2302168 -0.5013148 0.8652641 0.001211225 -0.5011278 0.851468 -0.1545095 -0.5015842 0.8116925 -0.2992804 -0.4979761 0.7813282 -0.3762262 -0.5018556 0.7459928 -0.4377622 -0.4979789 0.7015888 -0.5096962 -0.5014349 0.6628041 -0.5561059 -0.4996148 0.5986468 -0.6261047 -0.5012745 0.4896919 -0.7133904 -0.4996057 0.410508 -0.762809 -0.4982159 0.34074 -0.7972937 -0.5015674 0.2720524 -0.8212295 -0.4979734 0.1930391 -0.8454339 -0.5014418 0.1332077 -0.8548753 -0.4996232 0.03886651 -0.8653705 -0.4982227 -0.03890264 -0.8661759 -0.5012675 -0.1006398 -0.85942 -0.4994078 -0.2023345 -0.8424088 -0.4979703 -0.268017 -0.8247379 -0.5018336 -0.3336846 -0.7980086 -0.4979665 -0.4109538 -0.7636402 -0.5014303 -0.4621667 -0.7314162 -0.4996286 -0.5401191 -0.6772317 -0.4982191 -0.5992017 -0.6266858 -0.5012555 -0.6412756 -0.580955 -0.4996084 -0.7008308 -0.5091441 -0.501255 -0.7727468 -0.3893659 -0.4996123 -0.8110027 -0.304405 -0.4979794 -0.8359395 -0.2306983 -0.500866 -0.851617 -0.154537 -0.4982181 -0.8635609 -0.07772594 -0.5015295 -0.8651144 -0.006740689 -0.501044 -0.8571141 0.1196253 -0.5007032 -0.8336994 0.2328987 -0.5011074 -0.7797013 0.3754428 -0.4982289 -0.744291 0.444746 -0.5012571 -0.7090765 0.4959353 -0.4996299 -0.652319 0.5699562 -0.5015788 -0.5432609 0.6732656 -0.4979758 -0.4776885 0.7237637 -0.5018457 -0.4158739 0.7584193 -0.4979687 -0.3407956 0.7974243 -0.5014358 -0.2837116 0.8173555 -0.4996253 -0.1928278 0.8445069 -0.4982355 -0.1163175 0.8592042 -0.501631 -0.04214543 0.8640545 0.999983 0.005623877 0.001557826 1 0 -1.32738e-4 1 -1.62787e-4 0 1 2.26943e-4 -1.45525e-4 1 -3.01811e-4 -1.49399e-4 1 0 -1.44529e-4 0.9999991 0.001249372 6.64249e-4 1 0 -6.6534e-5 1 0 -4.35774e-5 1 -2.09908e-4 -4.80551e-4 1 -1.95618e-4 -2.21948e-4 1 -1.18892e-4 -2.35676e-4 1 0 -1.60477e-4 0.9999999 1.52501e-4 -5.20997e-4 1 0 -2.27555e-4 1 0 -1.46745e-4 1 -1.54799e-4 -2.13056e-5 1 0 -4.32825e-5 0.9999988 -0.001445055 6.44671e-4 0.9999997 -9.02934e-4 -2.2021e-4 1 0 -1.47119e-4 0.9999998 -2.02922e-4 -5.19831e-4 1 -5.24494e-5 -1.27905e-4 1 1.07643e-4 -9.85008e-5 1 0 -1.46343e-4 1 0 -1.32508e-4 1 4.39947e-4 -1.07585e-4 0.9999998 6.77201e-4 -2.20498e-4 1 -3.3087e-4 -1.08029e-4 1 -1.21714e-4 -2.96735e-4 1 0 -2.43556e-4 1 -3.8915e-5 -4.31548e-4 1 2.65067e-4 -2.09188e-4 1 0 -6.69105e-5 0.9999836 -0.005525708 0.001542687 1 0 -2.09825e-5 1 -7.43605e-5 -1.68832e-4 0.9999999 0 -4.90955e-4 1 0 -1.73685e-5 1 2.4616e-5 -1.7728e-4 1 0 -1.67776e-4 1 0 -2.30581e-4 0.00118184 0.9999994 -3.44929e-4 7.66584e-4 0.9999998 5.32996e-5 6.8718e-4 0.9999998 -1.08779e-5 7.40571e-4 0.9999998 1.33598e-5 7.50337e-4 0.9999998 -5.77318e-7 7.21067e-4 0.9999998 -6.44561e-6 7.42263e-4 0.9999998 2.9343e-5 7.46982e-4 0.9999998 6.91479e-6 7.83002e-4 0.9999998 2.12486e-4 7.53709e-4 0.9999998 1.3895e-5 7.45832e-4 0.9999997 -1.77436e-4 8.18856e-4 0.9999997 -1.90745e-4 7.36071e-4 0.9999998 -2.39928e-5 9.54509e-4 0.9999997 1.00433e-4 6.16512e-4 0.9999995 -8.6847e-4 7.11954e-4 0.9999998 2.8061e-5 6.83457e-4 0.9999998 1.90275e-4 -0.005077838 -0.9999871 -1.07593e-4 -0.005340397 -0.9999858 8.25443e-5 -0.00537163 -0.9999856 -1.90968e-5 -0.005407273 -0.9999855 -1.52389e-5 -0.005613029 -0.9999843 8.45852e-5 -0.005364596 -0.9999857 3.66221e-6 -0.005326271 -0.9999859 8.07971e-5 -0.005360484 -0.9999857 2.76482e-6 -0.005267679 -0.9999862 -3.87626e-5 -0.005362391 -0.9999856 -6.08927e-5 -0.005274116 -0.9999861 -3.47927e-5 -0.005403161 -0.9999853 -4.64963e-4 -0.005339622 -0.9999858 2.81815e-5 0 -0.04486793 -0.9989929 0 -0.1341542 -0.9909605 0 -0.2226023 -0.9749094 0 -0.3090617 -0.951042 0 -0.3929874 -0.9195439 0 -0.4738915 -0.8805832 0 -0.5508461 -0.8346068 0 -0.6235225 -0.7818055 0 -0.6910797 -0.7227786 0 -0.7530462 -0.6579677 0 -0.8090379 -0.5877566 0 -0.858424 -0.5129409 0 -0.9009878 -0.4338445 0 -0.9362241 -0.3514039 0 -0.9639644 -0.2660316 0 -0.9839317 -0.1785457 0 -0.9959736 -0.08964705 0 -0.995974 0.08964312 0 -0.9839313 0.1785476 0 -0.9639638 0.2660334 0 -0.9362241 0.3514039 0 -0.9009871 0.4338461 0 -0.8584231 0.5129424 0 -0.8090388 0.5877554 0 -0.7530473 0.6579666 0 -0.6910793 0.722779 0 -0.6235229 0.7818052 0 -0.5508457 0.8346071 0 -0.4738911 0.8805835 0 -0.3929871 0.919544 0 -0.3090617 0.951042 0 -0.2226023 0.9749094 0 -0.1341542 0.9909605 0 -0.04486793 0.9989929 0 0.04486793 0.9989929 0 0.1341542 0.9909605 0 0.2226023 0.9749094 0 0.3090617 0.951042 0 0.3929874 0.9195439 0 0.4738915 0.8805832 0 0.5508461 0.8346068 0 0.6235225 0.7818055 0 0.6910797 0.7227786 0 0.7530462 0.6579677 0 0.8090379 0.5877566 0 0.858424 0.5129409 0 0.9009878 0.4338445 0 0.9362241 0.3514039 0 0.9639644 0.2660316 0 0.9839317 0.1785457 0 0.9959736 0.08964705 0 0.995974 -0.08964312 0 0.9839313 -0.1785476 0 0.9639638 -0.2660334 0 0.9362241 -0.3514039 0 0.9009871 -0.4338461 0 0.8584231 -0.5129424 0 0.8090388 -0.5877554 0 0.7530473 -0.6579666 0 0.6910793 -0.722779 0 0.6235229 -0.7818052 0 0.5508457 -0.8346071 0 0.4738911 -0.8805835 0 0.3929871 -0.919544 0 0.3090617 -0.951042 0 0.2226023 -0.9749094 0 0.1341542 -0.9909605 0 0.04486793 -0.9989929 0 0.1341552 -0.9909604 0 0.2226032 -0.9749092 0 0.3090635 -0.9510415 0 0.3929874 -0.9195439 0 0.4738885 -0.880585 0 0.5508461 -0.8346068 0 0.6235201 -0.7818075 0 0.6910797 -0.7227786 0 0.7530462 -0.6579677 0 0.8090379 -0.5877566 0 0.8584229 -0.5129426 0 0.9009878 -0.4338445 0 0.9362231 -0.3514065 0 0.9639649 -0.2660295 0 0.9839317 -0.1785457 0 0.9959736 -0.08964705 0 0.995974 0.08964312 0 0.9839313 0.1785476 0 0.9639644 0.2660314 0 0.9362231 0.3514065 0 0.9009871 0.4338461 0 0.8584221 0.5129441 0 0.8090388 0.5877554 0 0.7530473 0.6579666 0 0.6910793 0.722779 0 0.6235205 0.781807 0 0.5508457 0.8346071 0 0.473888 0.8805851 0 0.3929871 0.919544 0 0.3090635 0.9510415 0 0.2226032 0.9749092 0 0.1341552 0.9909604 0 -0.1341552 0.9909604 0 -0.2226032 0.9749092 0 -0.3090635 0.9510415 0 -0.3929874 0.9195439 0 -0.4738885 0.880585 0 -0.5508461 0.8346068 0 -0.6235201 0.7818075 0 -0.6910797 0.7227786 0 -0.7530462 0.6579677 0 -0.8090379 0.5877566 0 -0.8584229 0.5129426 0 -0.9009878 0.4338445 0 -0.9362231 0.3514065 0 -0.9639649 0.2660295 0 -0.9839317 0.1785457 0 -0.9959736 0.08964705 0 -0.995974 -0.08964312 0 -0.9839313 -0.1785476 0 -0.9639644 -0.2660314 0 -0.9362231 -0.3514065 0 -0.9009871 -0.4338461 0 -0.8584221 -0.5129441 0 -0.8090388 -0.5877554 0 -0.7530473 -0.6579666 0 -0.6910793 -0.722779 0 -0.6235205 -0.781807 0 -0.5508457 -0.8346071 0 -0.473888 -0.8805851 0 -0.3929871 -0.919544 0 -0.3090635 -0.9510415 0 -0.2226032 -0.9749092 0 -0.1341552 -0.9909604 1 5.96681e-5 0 1 -9.376e-6 0 1 -8.88998e-5 0 1 1.55355e-5 0 1 4.09075e-6 0 1 -2.43982e-5 0 1 -7.53438e-6 0 1 -4.81616e-7 0 1 -1.42692e-5 0 1 4.29664e-5 0 1 -7.46146e-6 0 1 4.81615e-7 0 1 1.42692e-5 0 1 1.62235e-6 0 1 -6.26291e-6 0 1 1.63632e-5 0 1 -6.7494e-6 0 1 -2.61578e-6 0 1 8.71902e-6 0 1 -5.58447e-6 0 1 -8.71902e-6 0 1 1.44907e-5 0 1 -3.12537e-6 0 1 2.92042e-6 0 1 -1.58677e-5 0 1 6.26292e-6 0 1 2.61578e-6 0 1 -2.22607e-6 0 1 1.58677e-5 0 1 -1.63495e-5 0 1 -1.6796e-5 0 1 -1.44909e-5 0 1 -2.2099e-6 0 1 2.20987e-6 0 1 1.72224e-5 0 1 2.59568e-5 0 0.02749818 -0.8467763 0.5312382 0.0275073 -0.7888385 0.6139847 0.0275036 -0.7228513 0.690456 0.02752745 -0.6495831 0.7597921 0.02744865 -0.5694956 0.821536 0.02754551 -0.4837336 0.8747819 0.02740418 -0.4813143 0.8761197 0.02734833 -0.389629 0.9205657 0.02752596 -0.3929651 0.9191413 0.02724093 -0.2924484 0.9558933 0.02753847 -0.2982851 0.9540795 0.02730667 -0.1953151 0.9803604 0.02755433 -0.200506 0.9793049 0.02753174 0.3935162 0.9189054 0.02750188 0.4841036 0.8745785 0.02751845 0.5699779 0.8211992 0.02756226 0.6498536 0.7595595 0.02744048 0.7231965 0.6900971 0.02754408 0.7891654 0.6135627 0.02747082 0.7900571 0.6124176 0.02751123 0.8469246 0.5310009 0.02749919 0.8470563 0.5307915 0.02734857 0.8975228 0.4401193 0.02749222 0.896278 0.44264 0.02741891 0.1265057 0.9915869 0.02046805 0.07608157 0.9968916 0.0275774 0.1007216 0.9945324 0.02667814 0.2181589 0.9755486 0.02152121 0.1771166 0.9839546 0.02766329 0.2010079 0.9791989 0.02857744 0.2984426 0.9539997 0.02753621 0.3309583 0.9432436 0.02634066 0.308739 0.950782 0.02841764 0.2982379 0.9540686 0.02131271 0.2682844 0.963104 0.02433681 0.287677 0.9574182 0.02703565 0.3201559 0.9469791 0.02796816 0.3143407 0.9488983 0.03005754 0.2729356 0.9615628 0.02742195 0.2396377 0.9704751 0.02879393 0.1949946 0.9803816 0.02715104 0.1467064 0.9888074 0.03002786 0.0761345 0.9966453 0.02760416 -0.03150892 0.9991223 0.02783244 0.01522755 0.9994967 0.0288431 1.75314e-4 0.999584 0.0204612 -0.07053798 0.9972993 0.02794122 -0.09921085 0.9946742 0.02404505 -0.0899282 0.995658 0.02781623 -0.1233943 0.9919679 0.02748787 -0.1376996 0.9900926 0.02718096 -0.1279678 0.9914059 0.02841365 -0.105016 0.9940646 0.0263254 -0.1113386 0.9934338 0.03037887 -0.07319599 0.9968548 0.02747356 -0.1006261 0.994545 0.02392697 0.001457929 0.9997127 0.02646136 0.01574367 0.9995259 0.02714288 -0.03028506 0.9991728 0.027502 -0.8945302 0.4461607 0.02765309 -0.8960601 0.4430708 0.02722942 -0.9260938 0.3763097 0.02591902 -0.9626981 0.269334 0.02941524 0.9647688 0.2614496 0.02632677 0.9364044 0.3499341 0.02819734 0.9396196 0.3410572 0.02889984 -0.9361665 0.3503673 0.0271514 0.1011519 0.9945005 0.02831983 0.2008785 0.9792068 0.02768361 0.2988035 0.9539131 0.02724039 0.7204555 0.6929661 0.0274263 0.6477099 0.7613934 0.02745479 0.5690212 0.8218644 0.02739089 0.4820806 0.8756986 0.02748125 0.392551 0.9193196 0.02738231 -0.5705925 0.8207767 0.0274713 -0.650465 0.7590393 0.02744376 -0.7236693 0.6896011 0.02747178 -0.7892665 0.6134359 0.02749609 -0.8467988 0.5312023 0.9993622 0.03026485 -0.01895546 0.9959522 0.08820855 0.01728129 0.966686 0.2556217 -0.01325786 0.9562494 0.2922674 0.01291769 0.8706598 0.4918586 -0.005158126 0.8823839 0.4703751 0.01208645 0.7793177 0.6264676 0.01421749 0.6541579 0.756241 0.01330929 0.5132911 0.858176 0.008137285 0.3622458 0.9320147 0.01126271 0.2050434 0.9786937 0.01076596 0.04477417 0.9988587 0.01663565 -0.1161141 0.9931759 0.01091283 -0.0616393 0.9980335 -0.01140284 -0.2753363 0.9612777 0.01163238 -0.2365885 0.9715939 -0.005605757 -0.4000054 0.9164855 -0.007086575 -0.540234 0.8414925 -0.006143212 -0.711938 0.7020478 0.01652973 -0.6775573 0.735396 -0.01043456 -0.8281989 0.5602457 0.0145412 -0.8061729 0.5915974 -0.009889423 -0.9190108 0.3936364 0.02167284 -0.8985621 0.4386781 -0.01215875 -0.9779317 0.2078455 0.02120941 -0.9673888 0.2530283 -0.01165002 -0.9988623 0.04245239 -0.02172505 -0.9996478 0.02526295 -0.008127748 -0.5773777 0.81634 0.01496994 -0.4302619 0.9026561 0.009319245 0.1505532 0.988537 -0.01132965 0.3240178 0.946035 -0.005498349 0.4845494 0.8747364 -0.00694555 0.6195283 0.7849407 -0.007275581 0.753102 0.6578615 -0.007472574 -0.8988963 -0.4370075 0.03177899 -0.7931849 -0.6080737 -0.03322935 -0.676329 -0.7358732 0.03270667 -0.5497456 -0.8349879 -0.02398353 -0.3954811 -0.9178142 0.03481113 -0.2042214 -0.9788291 0.01368272 -0.06241708 -0.9980065 0.009341239 0.06580442 -0.9977954 0.008622646 0.1968193 -0.9804118 0.007416963 0.5673528 -0.8226361 0.03715807 0.9044859 -0.4255994 0.02775621 0.7987406 -0.6002218 -0.04180037 0.4595037 -0.8873844 -0.03748625 0.327135 -0.9445274 0.02916765 0.2280614 -0.9733505 -0.02401775 0.07714921 -0.996982 -0.008655369 -0.05134296 -0.9986437 -0.008640587 -0.1887728 -0.9819754 -0.009441316 -0.3506492 -0.9363786 -0.01550239 6.88013e-4 -6.05707e-4 0.9999996 -1.31513e-4 5.80846e-5 1 2.17659e-4 0 1 -3.10189e-5 0 1 6.44891e-5 0 1 1.00614e-4 0 1 0 1.27134e-4 1 -5.41655e-5 0 1 0 -4.84158e-5 1 4.61585e-5 0 1 -4.79731e-5 0 1 -2.41323e-6 0 1 7.04171e-6 0 1 -7.46938e-5 0 1 1.48452e-5 0 1 1.05514e-4 4.46331e-5 1 1.87476e-5 0 1 8.63881e-5 0 1 -6.57309e-5 0 1 -4.64425e-5 0 1 -6.8339e-5 0 1 0.3357588 0.7062994 0.6232232 0.3320914 0.6567645 0.6770345 0.3354843 0.6598522 0.6723433 0.3352842 0.5915672 0.7332345 0.3344165 0.5195581 0.7862728 0.3339887 0.5149991 0.7894477 0.3335921 0.4398314 0.8338254 0.334314 0.4473516 0.8295245 0.3310417 0.2481819 0.910394 0.3340682 0.2348043 0.9128338 0.3326041 0.320998 0.8867552 0.3289895 0.2979529 0.8960971 0.3333342 0.3162233 0.8881955 0.3353627 0.3625136 0.8695492 0.3351833 0.3653717 0.8684215 0.3341232 0.3960882 0.8552637 0.3288161 0.3638057 0.8715075 0.3312506 0.3753718 0.8656611 0.3333587 0.3801099 0.8627796 0.3417559 0.3722645 0.8629149 0.3326347 0.3836649 0.8614844 0.334023 0.3946164 0.8559828 0.3346464 0.3774378 0.8634538 0.3341807 0.299193 0.89376 0.3339895 0.3185148 0.8871299 0.3346089 0.3468217 0.8762144 0.3322762 0.2338189 0.9137403 0.3345798 0.1890517 0.9232096 0.3351682 0.1709243 0.9265242 0.3328227 0.06328725 0.9408633 0.3339756 -0.02221238 0.94232 0.3329557 -0.03022009 0.9424582 0.3325336 -0.1025387 0.9375005 0.3324592 -0.1031216 0.9374631 0.3322841 -0.173495 0.9270851 0.3349334 -0.1678444 0.927172 0.3354174 -0.2543489 0.9070842 0.3318964 -0.2094085 0.9197787 0.3343644 -0.2808772 0.8996158 0.3343579 -0.304403 0.8919326 0.3348743 -0.3355236 0.8805018 0.3237944 -0.3160691 0.8917721 0.3348032 -0.3449376 0.8768837 0.3347956 -0.345287 0.876749 0.3353219 -0.3346197 0.8806753 0.3352902 -0.3350895 0.8805087 0.3333924 -0.4184482 0.8448376 0.3348701 -0.4981123 0.7998415 0.3342592 -0.4935875 0.8028962 0.3338701 -0.5548568 0.7620137 0.3349193 -0.5628312 0.7556786 0.3316428 -0.6228526 0.7085675 0.334737 -0.6855117 0.6465485 0.3376194 -0.6328699 0.6967704 0.3328903 -0.4147338 0.8468647 0.3356505 0.04667234 0.9408298 0.3308107 0.1286965 0.9348805 0.3355517 0.2712941 0.9021112 0.333908 0.3448956 0.8772415 0.3340584 0.2784172 0.9004938 0.33255 0.5816687 0.7423422 0.00121659 -0.9999921 0.003812074 0.001581549 -0.9999979 -0.001360952 0.1469245 -0.6657434 0.7315729 0.1491685 -0.5886347 0.7945175 0.1466065 -0.5190213 0.8420947 0.1488006 -0.4714437 0.8692522 0.1471834 -0.4366714 0.8874995 0.1486546 -0.3906342 0.908464 0.146571 -0.3537778 0.923774 0.1468604 -0.2623411 0.9537343 0.1484534 -0.2900876 0.9454157 0.1477827 0.3833071 0.9117215 0.1472033 0.3894078 0.9092265 0.1474271 0.4630671 0.873976 0.1470044 0.543775 0.8262557 0.1486505 0.6242281 0.7669696 0.147053 0.6868646 0.7117532 0.1487418 -0.7127 0.6855179 0.1479822 -0.7882553 0.5972896 0.1502113 -0.8434459 0.5157865 0.1539524 0.8878813 0.4335498 0.1451122 0.8388555 0.5246561 0.1492522 0.8435084 0.5159626 0.1471627 0.7806991 0.6073319 0.1487293 0.7868761 0.5989205 0.1477004 0.738568 0.6578008 0.1480926 0.2944023 0.9441376 0.1464489 0.2816094 0.9482874 0.1551635 0.1719474 0.9728096 0.1490296 0.2117362 0.9658975 0.1477608 0.2420075 0.9589574 0.1508188 0.1007727 0.9834117 0.1504316 0.1021955 0.9833242 0.1522257 0.001199901 0.988345 0.1474083 0.03284293 0.9885303 0.1461634 -0.09688556 0.9845048 0.1554993 -0.06930482 0.9854019 0.1482241 -0.1990635 0.9687122 0.147163 -0.1828279 0.9720684 0.1527093 -0.1749666 0.9726596 0.1463879 -0.1912661 0.9705607 0.1560702 -0.1594418 0.9747925 0.1486666 -0.1169542 0.9819471 0.1488398 -0.01817691 0.9886943 0.1465846 0.1978777 0.9692046 0.1479911 0.2949125 0.9439944 0.1512814 -0.8830103 0.4443047 0.1447413 -0.8383727 0.5255295 0.1455372 -0.7815121 0.6066777 0.1484743 -0.7159622 0.6821683 0.1489692 0.7127519 0.6854144 0.1463437 0.6427789 0.7519435 0.1484088 0.562489 0.8133763 0.1483436 0.4753378 0.8672071 0.1459345 -0.5646452 0.8123294 0.1485156 -0.6444553 0.7500804 8.39756e-5 7.12542e-5 1 1.41496e-5 0 1 0 -1.82071e-5 1 0 2.26166e-5 1 -2.50591e-6 -1.78032e-7 1 -1.08808e-5 0 1 1.70674e-5 0 1 5.82541e-6 -2.44498e-5 1 -5.91574e-6 0 1 -2.96295e-4 0 1 -4.20176e-6 1.37357e-5 1 7.68694e-4 0.9999775 -0.006673753 0 1 3.74435e-4 0.9680913 -0.2505125 0.006549954 0.9609892 -0.2765805 -0.001734316 0.9993929 -0.03479677 -0.001798391 0.9975993 -0.06877392 0.008116006 0.9918487 0.1273432 -0.004469513 0.9881481 0.1534841 0.002464652 0.9417352 0.3363263 0.004422426 0.8618066 0.5071313 0.01035445 0.7744086 0.6326684 -0.004694283 0.7512682 0.6599841 0.004139721 0.613973 0.7893151 0.004347801 0.4548643 0.8905113 0.009385406 0.3013643 0.9534609 -0.009588479 0.09429919 0.9954864 0.01070296 0.279559 0.9601259 -0.002247035 0.5715132 0.8205482 -0.008561611 0.9208416 0.3898217 -0.009479284 0.3334321 -0.9427698 0.002877533 0.3182151 -0.947997 0.006393313 0.5861635 -0.8101898 -0.002214312 0.5623055 -0.8269222 0.003498077 0.7919211 -0.6106157 0.003108322 0.8044343 -0.5940387 -0.001936554 -9.85523e-5 1 -8.95459e-5 1.03683e-5 1 2.18498e-5 2.07842e-4 1 0 0 1 0 0 1 0 0 -1 0 0 -1 -4.19457e-7 -7.40424e-5 -1 -4.90593e-5 0 -1 -1.68696e-7 0 -1 1.76428e-7 1.65833e-4 -1 -1.31834e-4 -2.65616e-5 -1 -5.83586e-5 0 -1 -2.77768e-7 -1.66904e-4 -0.9999998 -7.04732e-4 0 -1 0 -1.31694e-7 -1 0 0 -1 -1.84854e-7 -2.88014e-4 -1 1.15877e-4 0 -1 1.09154e-6 0 -1 3.18366e-7 -1.24107e-7 -1 4.58102e-7 0 -1 1.95201e-7 2.86565e-7 -1 4.80663e-7 0 -1 -1.04949e-6 -1 0 1.91228e-6 -1 -7.27455e-7 -3.18681e-6 -1 0 -1.75475e-6 -1 0 -1.88469e-6 -1 3.08278e-6 0 -1 0 -1.45575e-6 -1 3.14968e-6 0 -1 2.34081e-6 0 -1 -7.51833e-6 0 -1 -3.47039e-6 0 -1 -3.91067e-7 0 -1 1.31101e-7 0 -1 3.26034e-7 0 + + + + + + + + + + + + + + +

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

+
+
+
+ + + + 122 20.25 1191.299 122 36.25 1207.299 122 36.25 1191.299 -69.7 20.25 1191.299 -69.7 36.25 1207.299 127 36.25 1191.299 122 -20.25 1191.299 -69.7 -20.25 1191.299 127 -36.25 1191.299 122 -36.25 1191.299 122 -36.25 1207.299 -69.7 -36.25 1207.299 127 36.25 1263.799 127 -36.25 1263.799 122 -36.25 1247.799 -69.7 -36.25 1247.799 122 -36.25 1263.799 122 -20.25 1263.799 -69.7 -20.25 1263.799 -69.7 36.25 1247.799 -69.7 20.25 1263.799 122 20.25 1263.799 122 36.25 1263.799 122 36.25 1247.799 + + + + + + + + + + -1 0 0 0 0.7071068 -0.7071068 0 0.7071068 -0.7071068 0 0 -1 0 -0.7071068 -0.7071068 0 -0.7071068 -0.7071068 1 0 0 0 -1 0 0 -0.7071068 0.7071068 0 -0.7071068 0.7071068 0 0 1 0 1 0 0 0.7071068 0.7071068 0 0.7071068 0.7071068 + + + + + + + + + + + + + + +

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

+
+
+
+ + + + 95.5 20.25 1283.749 95.5 36.25 1299.749 95.5 36.25 1283.749 -96.2 20.25 1283.749 -96.2 36.25 1299.749 100.5 36.25 1283.749 95.5 -20.25 1283.749 -96.2 -20.25 1283.749 100.5 -36.25 1283.749 95.5 -36.25 1283.749 95.5 -36.25 1299.749 -96.2 -36.25 1299.749 100.5 36.25 1356.249 100.5 -36.25 1356.249 95.5 -36.25 1340.249 -96.2 -36.25 1340.249 95.5 -36.25 1356.249 95.5 -20.25 1356.249 -96.2 -20.25 1356.249 -96.2 36.25 1340.249 -96.2 20.25 1356.249 95.5 20.25 1356.249 95.5 36.25 1356.249 95.5 36.25 1340.249 + + + + + + + + + + -1 0 0 0 0.7071068 -0.7071068 0 0.7071068 -0.7071068 0 0 -1 0 -0.7071068 -0.7071068 0 -0.7071068 -0.7071068 1 0 0 0 -1 0 0 -0.7071068 0.7071068 0 -0.7071068 0.7071068 0 0 1 0 1 0 0 0.7071068 0.7071068 0 0.7071068 0.7071068 + + + + + + + + + + + + + + +

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

+
+
+
+ + + + 103 20.37815 1376.327 103 36.37815 1392.327 103 36.37815 1376.327 -88.7 20.37815 1376.327 -88.7 36.37815 1392.327 103 -20.12185 1376.327 -88.7 -20.12185 1376.327 108 -36.12185 1376.327 103 -36.12185 1376.327 108 36.37815 1376.327 103 -36.12185 1392.327 -88.7 -36.12185 1392.327 108 36.37815 1448.827 108 -36.12185 1448.827 103 -36.12185 1432.827 -88.7 -36.12185 1432.827 103 -36.12185 1448.827 103 -20.12185 1448.827 -88.7 -20.12185 1448.827 -88.7 36.37815 1432.827 -88.7 20.37815 1448.827 103 20.37815 1448.827 103 36.37815 1448.827 103 36.37815 1432.827 + + + + + + + + + + -1 0 0 0 0.7071068 -0.7071068 0 0.7071068 -0.7071068 0 0 -1 0 -0.7071068 -0.7071068 1 0 0 0 -1 0 0 -0.7071068 0.7071068 3.85802e-5 0 1 0 0 1 0 1 0 0 0.7071068 0.7071068 0 0.7071068 0.7071068 + + + + + + + + + + + + + + +

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

+
+
+
+ + + + 184.6715 43 1369.305 184.6715 43 1341.021 170.5294 43 1355.163 184.6715 213 1369.305 184.6715 213 1341.021 245.7302 213 1430.364 259.8723 36 1444.506 259.8723 43 1444.506 245.7302 43 1430.364 170.5294 36 1355.163 274.0144 43 1430.364 274.0144 213 1430.364 259.8723 36 1265.82 349.2153 36 1355.163 335.0731 43 1369.305 335.0731 213 1369.305 349.2153 43 1355.163 335.0731 43 1341.021 335.0731 213 1341.021 274.0144 213 1279.962 245.7302 213 1279.962 245.7302 43 1279.962 259.8723 43 1265.82 274.0144 43 1279.962 + + + + + + + + + + 0 1 0 -1 0 0 -0.7071076 0 0.7071061 -0.7071042 0 0.7071094 -0.7071079 0 0.7071057 -0.7071076 -2.58499e-5 0.707106 -0.7071086 0 0.7071051 -0.7071051 0 0.7071085 0 0 1 0 -1 0 0.707108 -1.2925e-5 0.7071056 0.7071076 0 0.707106 0.7071087 0 0.707105 0.707102 0 0.7071116 0.7071076 8.83316e-6 0.7071059 0.7071051 0 0.7071085 1 0 0 -0.7071076 -1.61562e-5 -0.707106 -0.7071076 0 -0.7071061 -0.7071086 0 -0.7071051 -0.7070981 0 -0.7071155 -0.7071079 1.32497e-5 -0.7071057 -0.7071112 0 -0.7071025 0.7071087 0 -0.707105 0.707112 0 -0.7071015 0.7071076 2.64995e-5 -0.7071059 0.707108 -6.46248e-6 -0.7071056 0.7071076 0 -0.707106 0.707095 0 -0.7071186 0 0 -1 + + + + + + + + + + + + + + +

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

+
+
+
+
+ + + + + 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 + + + + 0.00100089 0 0 -0.26 0 0.001 0 0 0 0 0.001 -1.355 0 0 0 1 + + + + + + + + + + 0.001001525 0 0 -0.26 0 0.001 0 0 0 0 0.001 -1.355 0 0 0 1 + + + + + + + + + + 0.001001525 0 0 -0.26 0 0.001 0 0 0 0 0.001 -1.355 0 0 0 1 + + + + + + + + + + 0.001001525 0 0 -0.26 0 0.001006896 0 0 0 0 0.001 -1.355 0 0 0 1 + + + + + + + + + + 0.001001758 0 0 -0.26 0 0.001 0 0 0 0 0.001 -1.355 0 0 0 1 + + + + + + + + + + + + + +
\ No newline at end of file diff --git a/kuka_kr16_support/meshes/kr16_2/visual/link_4.dae b/kuka_kr16_support/meshes/kr16_2/visual/link_4.dae new file mode 100644 index 000000000..4c42ecc0b --- /dev/null +++ b/kuka_kr16_support/meshes/kr16_2/visual/link_4.dae @@ -0,0 +1,198 @@ + + + + + Blender User + Blender 2.79.0 commit date:2017-09-11, commit time:10:43, hash:5bd8ac9abfa + + 2017-11-10T20:35:45 + 2017-11-10T20:35:45 + + 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.512 0.2088141 0.07027201 1 + + + 0.015625 0.015625 0.015625 1 + + + 1 + + + 1 + + + + + + + + + + + + + + + + 662 76.02439 1307.781 662 76.50172 1328.746 662 76.98005 1321.753 662 -76.50172 1328.746 662 -64.86254 1361.495 662 -60.82044 1367.222 662 -75.38948 1335.666 662 -73.65253 1342.457 662 -71.30529 1349.061 662 -56.27437 1372.557 662 -53.82396 1264.937 662 -58.60814 1270.059 662 75.38948 1335.666 662 -68.36717 1355.425 662 -76.82051 1314.745 662 -76.98005 1321.753 662 -72.5541 1294.214 662 -74.59832 1300.919 662 -62.90668 1275.596 662 64.86254 1361.495 662 72.5541 1294.214 662 69.90867 1287.723 662 73.65253 1342.457 662 74.59832 1300.919 662 68.36717 1355.425 662 -30.67688 1249.375 662 -33.85957 1389.156 662 -27.43061 1391.948 662 -76.02439 1307.781 662 -69.90867 1287.723 662 -66.68395 1281.5 662 36.97208 1252.457 662 30.67688 1249.375 662 58.60814 1270.059 662 53.82396 1264.937 662 76.82051 1314.745 662 71.30529 1349.061 662 -40.00796 1385.79 662 24.12749 1246.878 662 48.59377 1260.27 662 66.68395 1281.5 662 -45.82484 1381.88 662 -51.26199 1377.456 662 -36.97208 1252.457 662 17.37816 1244.987 662 62.90668 1275.596 662 10.48483 1243.717 662 51.26199 1377.456 662 56.27437 1372.557 662 -48.59377 1260.27 662 -42.96092 1256.099 662 42.96092 1256.099 662 60.82044 1367.222 662 2.250796 1243.004 662 13.94595 1395.727 662 20.77435 1394.145 662 -20.77435 1394.145 662 0 1397 662 -17.37816 1244.987 662 -24.12749 1246.878 662 45.82484 1381.88 662 33.85957 1389.156 662 40.00796 1385.79 662 27.43061 1391.948 662 -13.94595 1395.727 662 -7.001985 1396.681 662 -10.48483 1243.717 662 7.001985 1396.681 662 -3.504624 1243.08 722.5 -7.001985 1396.681 722.5 0 1397 722.5 -13.94595 1395.727 722.5 -20.77435 1394.145 722.5 -27.43061 1391.948 722.5 -33.85957 1389.156 722.5 -40.00796 1385.79 722.5 -45.82484 1381.88 722.5 -51.26199 1377.456 722.5 -56.27437 1372.557 722.5 -60.82044 1367.222 722.5 -64.86254 1361.495 722.5 -68.36717 1355.425 722.5 -71.30529 1349.061 722.5 -73.65253 1342.457 722.5 -75.38948 1335.666 722.5 -76.50172 1328.746 722.5 -76.98005 1321.753 722.5 -76.82051 1314.745 722.5 -76.02439 1307.781 722.5 -74.59832 1300.919 722.5 -72.5541 1294.214 722.5 -69.90867 1287.723 722.5 -66.68395 1281.5 722.5 -62.90668 1275.596 722.5 -58.60814 1270.059 722.5 -53.82396 1264.937 722.5 -48.59377 1260.27 722.5 -42.96092 1256.099 722.5 -36.97208 1252.457 722.5 -30.67688 1249.375 722.5 -24.12749 1246.878 722.5 -17.37816 1244.987 722.5 -10.48483 1243.717 722.5 -3.504624 1243.08 722.5 3.504624 1243.08 722.5 10.48483 1243.717 722.5 17.37816 1244.987 722.5 24.12749 1246.878 722.5 30.67688 1249.375 722.5 36.97208 1252.457 722.5 42.96092 1256.099 722.5 48.59377 1260.27 722.5 53.82396 1264.937 722.5 58.60814 1270.059 722.5 62.90668 1275.596 722.5 66.68395 1281.5 722.5 69.90867 1287.723 722.5 72.5541 1294.214 722.5 74.59832 1300.919 722.5 76.02439 1307.781 722.5 76.82051 1314.745 722.5 76.98005 1321.753 722.5 76.50172 1328.746 722.5 75.38948 1335.666 722.5 73.65253 1342.457 722.5 71.30529 1349.061 722.5 68.36717 1355.425 722.5 64.86254 1361.495 722.5 60.82044 1367.222 722.5 56.27437 1372.557 722.5 51.26199 1377.456 722.5 45.82484 1381.88 722.5 40.00796 1385.79 722.5 33.85957 1389.156 722.5 27.43061 1391.948 722.5 20.77435 1394.145 722.5 13.94595 1395.727 722.5 7.001985 1396.681 722.5 71.73948 1341.873 722.5 69.4532 1348.306 722.5 -74.04972 1308.099 722.5 -74.82516 1314.882 722.5 -72.66069 1301.414 722.5 -68.09286 1288.562 722.5 -64.95191 1282.5 722.5 72.66069 1301.414 722.5 70.66957 1294.884 722.5 74.04972 1308.099 722.5 74.98057 1321.707 722.5 74.82516 1314.882 722.5 74.51467 1328.519 722.5 73.43132 1335.259 722.5 -73.43132 1335.259 722.5 -71.73948 1341.873 722.5 -74.51467 1328.519 722.5 -70.66957 1294.884 722.5 -74.98057 1321.707 722.5 -69.4532 1348.306 722.5 -57.08585 1271.356 722.5 -52.42593 1266.367 722.5 64.95191 1282.5 722.5 68.09286 1288.562 722.5 66.5914 1354.505 722.5 63.17779 1360.417 722.5 54.8127 1371.192 722.5 49.93051 1375.964 722.5 -61.27274 1276.749 722.5 61.27274 1276.749 722.5 44.63458 1380.272 722.5 -63.17779 1360.417 722.5 -59.24069 1365.995 722.5 -66.5914 1354.505 722.5 59.24069 1365.995 722.5 -54.8127 1371.192 722.5 41.84505 1257.759 722.5 47.3316 1261.822 722.5 52.42593 1266.367 722.5 57.08585 1271.356 722.5 -44.63458 1380.272 722.5 -38.96879 1384.081 722.5 -49.93051 1375.964 722.5 -47.3316 1261.822 722.5 -41.84505 1257.759 722.5 36.01177 1254.211 722.5 -6.820115 1394.689 722.5 0 1395 722.5 -13.58372 1393.76 722.5 -26.71813 1390.08 722.5 -20.23476 1392.219 722.5 -32.9801 1387.36 722.5 -36.01177 1254.211 722.5 -29.88008 1251.209 722.5 23.5008 1248.777 722.5 16.92678 1246.935 722.5 29.88008 1251.209 722.5 38.96879 1384.081 722.5 32.9801 1387.36 722.5 26.71813 1390.08 722.5 20.23476 1392.219 722.5 13.58372 1393.76 722.5 6.820115 1394.689 722.5 -23.5008 1248.777 722.5 -3.413595 1245.078 722.5 0 1245 722.5 10.2125 1245.699 722.5 3.413595 1245.078 722.5 -16.92678 1246.935 722.5 -10.2125 1245.699 739.5 -6.820115 1394.689 739.5 0 1395 739.5 -13.58372 1393.76 739.5 -20.23476 1392.219 739.5 -26.71813 1390.08 739.5 -32.9801 1387.36 739.5 -38.96879 1384.081 739.5 -44.63458 1380.272 739.5 -49.93051 1375.964 739.5 -54.8127 1371.192 739.5 -59.24069 1365.995 739.5 -63.17779 1360.417 739.5 -66.5914 1354.505 739.5 -69.4532 1348.306 739.5 -71.73948 1341.873 739.5 -73.43132 1335.259 739.5 -74.51467 1328.519 739.5 -74.98057 1321.707 739.5 -74.82516 1314.882 739.5 -74.04972 1308.099 739.5 -72.66069 1301.414 739.5 -70.66957 1294.884 739.5 -68.09286 1288.562 739.5 -64.95191 1282.5 739.5 -61.27274 1276.749 739.5 -57.08585 1271.356 739.5 -52.42593 1266.367 739.5 -47.3316 1261.822 739.5 -41.84505 1257.759 739.5 -36.01177 1254.211 739.5 -29.88008 1251.209 739.5 -23.5008 1248.777 739.5 -16.92678 1246.935 739.5 -10.2125 1245.699 739.5 -3.413595 1245.078 739.5 3.413595 1245.078 739.5 0 1245 739.5 10.2125 1245.699 739.5 16.92678 1246.935 739.5 23.5008 1248.777 739.5 29.88008 1251.209 739.5 36.01177 1254.211 739.5 41.84505 1257.759 739.5 47.3316 1261.822 739.5 52.42593 1266.367 739.5 57.08585 1271.356 739.5 61.27274 1276.749 739.5 64.95191 1282.5 739.5 68.09286 1288.562 739.5 70.66957 1294.884 739.5 72.66069 1301.414 739.5 74.04972 1308.099 739.5 74.82516 1314.882 739.5 74.98057 1321.707 739.5 74.51467 1328.519 739.5 73.43132 1335.259 739.5 71.73948 1341.873 739.5 69.4532 1348.306 739.5 66.5914 1354.505 739.5 63.17779 1360.417 739.5 59.24069 1365.995 739.5 54.8127 1371.192 739.5 49.93051 1375.964 739.5 44.63458 1380.272 739.5 38.96879 1384.081 739.5 32.9801 1387.36 739.5 26.71813 1390.08 739.5 20.23476 1392.219 739.5 13.58372 1393.76 739.5 6.820115 1394.689 739.5 60.66735 1299.617 739.5 58.33638 1293.678 739.5 62.39538 1305.759 739.5 43.53105 1273.085 739.5 47.986 1277.652 739.5 55.42562 1288 739.5 63.82104 1324.783 739.5 51.96403 1282.64 739.5 63.98011 1318.404 739.5 63.50331 1312.042 739.5 61.60795 1337.334 739.5 59.57592 1343.382 739.5 -63.02769 1331.114 739.5 -61.60795 1337.334 739.5 -63.82104 1324.783 739.5 -63.98011 1318.404 739.5 -63.50331 1312.042 739.5 -62.39538 1305.759 739.5 15.79247 1257.979 739.5 9.538705 1256.715 739.5 21.88929 1259.86 739.5 63.02769 1331.114 739.5 -59.57592 1343.382 739.5 27.76856 1262.338 739.5 33.37185 1265.389 739.5 45.81548 1364.687 739.5 50.03722 1359.903 739.5 41.13841 1369.027 739.5 30.60826 1376.206 739.5 36.05248 1372.879 739.5 -56.9518 1349.197 739.5 -58.33638 1293.678 739.5 -55.42562 1288 739.5 38.64348 1268.984 739.5 56.9518 1349.197 739.5 53.76166 1354.723 739.5 24.85983 1378.974 739.5 -45.81548 1364.687 739.5 -50.03722 1359.903 739.5 -60.66735 1299.617 739.5 -51.96403 1282.64 739.5 -47.986 1277.652 739.5 -43.53105 1273.085 739.5 -38.64348 1268.984 739.5 2.044188 1256.004 739.5 18.86433 1381.157 739.5 -24.85983 1378.974 739.5 -18.86433 1381.157 739.5 -30.60826 1376.206 739.5 -53.76166 1354.723 739.5 -27.76856 1262.338 739.5 12.68135 1382.731 739.5 6.372342 1383.682 739.5 0 1384 739.5 -6.372342 1383.682 739.5 -12.68135 1382.731 739.5 -36.05248 1372.879 739.5 -33.37185 1265.389 739.5 -21.88929 1259.86 739.5 -15.79247 1257.979 739.5 -9.538705 1256.715 739.5 -41.13841 1369.027 739.5 -3.190137 1256.08 755 -6.372342 1383.682 755 0 1384 755 -12.68135 1382.731 755 -18.86433 1381.157 755 -24.85983 1378.974 755 -30.60826 1376.206 755 -36.05248 1372.879 755 -41.13841 1369.027 755 -45.81548 1364.687 755 -50.03722 1359.903 755 -53.76166 1354.723 755 -56.9518 1349.197 755 -59.57592 1343.382 755 -61.60795 1337.334 755 -63.02769 1331.114 755 -63.82104 1324.783 755 -63.98011 1318.404 755 -63.50331 1312.042 755 -62.39538 1305.759 755 -60.66735 1299.617 755 -58.33638 1293.678 755 -55.42562 1288 755 -51.96403 1282.64 755 -47.986 1277.652 755 -43.53105 1273.085 755 -38.64348 1268.984 755 -33.37185 1265.389 755 -27.76856 1262.338 755 -21.88929 1259.86 755 -15.79247 1257.979 755 -9.538705 1256.715 755 -3.190137 1256.08 755 3.190137 1256.08 755 9.538705 1256.715 755 15.79247 1257.979 755 21.88929 1259.86 755 27.76856 1262.338 755 33.37185 1265.389 755 38.64348 1268.984 755 43.53105 1273.085 755 47.986 1277.652 755 51.96403 1282.64 755 55.42562 1288 755 58.33638 1293.678 755 60.66735 1299.617 755 62.39538 1305.759 755 63.50331 1312.042 755 63.98011 1318.404 755 63.82104 1324.783 755 63.02769 1331.114 755 61.60795 1337.334 755 59.57592 1343.382 755 56.9518 1349.197 755 53.76166 1354.723 755 50.03722 1359.903 755 45.81548 1364.687 755 41.13841 1369.027 755 36.05248 1372.879 755 30.60826 1376.206 755 24.85983 1378.974 755 18.86433 1381.157 755 12.68135 1382.731 755 6.372342 1383.682 755 67.35176 1321.628 755 64.07405 1340.819 755 65.78424 1334.538 755 66.88021 1328.121 755 67.19445 1315.12 755 66.40979 1308.658 755 65.00505 1302.301 755 62.99338 1296.11 755 60.39356 1290.142 755 57.22986 1284.452 755 -66.40979 1308.658 755 -67.19445 1315.12 755 -67.35176 1321.628 755 -66.88021 1328.121 755 -65.78424 1334.538 755 -64.07405 1340.819 755 53.53183 1279.095 755 49.33398 1274.119 755 44.67552 1269.572 755 39.59993 1265.495 755 -61.7656 1346.906 755 47.05971 1368.211 755 51.49304 1363.444 755 22.36111 1256.448 755 16.12304 1254.586 755 9.734435 1253.336 755 -44.67552 1269.572 755 -49.33398 1274.119 755 -53.53183 1279.095 755 -57.22986 1284.452 755 -60.39356 1290.142 755 -62.99338 1296.11 755 -58.88047 1352.741 755 -55.4456 1358.271 755 55.4456 1358.271 755 58.88047 1352.741 755 61.7656 1346.906 755 28.39039 1258.903 755 -65.00505 1302.301 755 34.15461 1261.928 755 -39.59993 1265.495 755 -51.49304 1363.444 755 -47.05971 1368.211 755 -42.18699 1372.528 755 31.30906 1379.654 755 36.92038 1376.354 755 42.18699 1372.528 755 3.254941 1252.707 755 -3.254941 1252.707 755 -16.12304 1254.586 755 -22.36111 1256.448 755 -28.39039 1258.903 755 -34.15461 1261.928 755 25.40542 1382.398 755 -9.734435 1253.336 755 -31.30906 1379.654 755 -25.40542 1382.398 755 -19.26457 1384.558 755 19.26457 1384.558 755 -12.94385 1386.116 755 12.94385 1386.116 755 -36.92038 1376.354 755 -6.502281 1387.057 755 6.502281 1387.057 755 0 1387.371 772.9996 -5.511342 1387.776 772.9996 -11.99044 1386.935 773.0009 -18.35761 1385.475 773.0001 -24.55889 1383.41 773.0009 -30.52978 1380.761 773 -36.21766 1377.552 772.9987 -41.57127 1373.813 772.9992 -46.54322 1369.575 772.9993 -51.08653 1364.88 772.9997 -55.1579 1359.77 773.0003 -58.71974 1354.293 773 -61.73939 1348.5 773.0003 -64.18922 1342.444 773 -66.04659 1336.182 773 -67.29466 1329.769 773 -67.92151 1323.266 773.0001 -67.92152 1316.734 773 -67.2946 1310.231 773.0005 -66.0465 1303.818 773.0004 -64.18884 1297.555 772.9997 -61.73894 1291.499 773.0004 -58.71892 1285.706 773.0001 -55.1584 1280.231 773.0007 -51.08686 1275.121 773.0015 -46.54312 1270.424 772.9984 -41.57639 1266.191 772.9997 -36.21894 1262.448 772.9996 -30.52685 1259.238 773.001 -24.55554 1256.589 772.9995 -18.36047 1254.526 772.9993 -11.9923 1253.065 773 -5.511425 1252.224 773.002 1.023305 1252.008 773.0008 7.537819 1252.419 772.9998 13.98545 1253.454 773.0006 20.30647 1255.103 772.9984 26.4378 1257.35 773 32.33127 1260.178 773.0006 37.92295 1263.556 773.0006 43.16568 1267.458 773.0003 48.00806 1271.841 772.9998 52.40629 1276.669 772.9997 56.32176 1281.897 773 59.71878 1287.478 773.0002 62.56423 1293.359 772.9991 64.83118 1299.484 772.9225 66.53917 1305.969 772.9996 64.832 1340.514 773 62.56405 1346.641 772.9996 59.71944 1352.521 773.0008 56.32208 1358.103 772.9999 52.406 1363.332 772.9996 48.00707 1368.16 773 43.16397 1372.544 772.9992 37.9253 1376.442 773.0003 32.32913 1379.823 772.9979 26.44395 1382.648 772.9995 20.3072 1384.897 772.9998 13.98639 1386.546 773.0003 7.534664 1387.581 772.9996 1.012406 1387.992 772.9999 66.50111 1334.199 773.0157 67.50215 1328.205 766.6874 67.49996 1326.195 759.7758 67.50118 1322.47 762.6853 67.49991 1315.516 758.8431 67.50067 1318.963 767.9057 67.50013 1313.368 773.0704 67.5014 1311.803 785.2194 67.49947 1316.628 786.9993 67.49957 1321.533 787 67.5 1318.775 782.9052 67.49996 1324.611 787 66.02297 1305.903 787 64.3656 1299.633 787 62.11417 1293.55 787 59.28948 1287.712 787 55.91759 1282.172 787 52.02962 1276.981 787 47.66146 1272.186 787 42.85341 1267.834 787 37.64986 1263.962 787 32.09882 1260.608 787 26.25154 1257.802 787 20.16197 1255.57 787 13.88632 1253.932 787 7.48251 1252.905 787 1.009642 1252.496 787 -5.472545 1252.711 787 -11.90422 1253.547 787 -18.22603 1254.996 787 -24.37963 1257.045 787 -30.30822 1259.675 787 -35.95709 1262.861 787 -41.2741 1266.575 787 -46.21018 1270.782 787 -50.71977 1275.444 787 -54.76125 1280.516 787 -58.29733 1285.953 787 -61.29536 1291.705 787 -63.72768 1297.717 787 -65.57184 1303.935 787 -66.81082 1310.301 787 -67.43318 1316.757 787 -67.43318 1323.243 787 -66.81082 1329.699 787 -65.57184 1336.065 787 -63.72768 1342.283 787 -61.29536 1348.295 787 -58.29733 1354.047 787 -54.76125 1359.484 787 -50.71977 1364.556 787 -46.21018 1369.218 787 -41.2741 1373.425 787 -35.95709 1377.139 787 -30.30822 1380.325 787 -24.37963 1382.955 787 -18.22603 1385.004 787 -11.90422 1386.453 787 -5.472545 1387.289 787 1.009642 1387.504 787 7.48251 1387.095 787 13.88632 1386.067 787 20.16197 1384.43 787 26.25154 1382.198 787 32.09882 1379.392 787 37.64986 1376.038 787 42.85341 1372.166 787 47.66146 1367.814 787 52.02962 1363.019 787 55.91759 1357.828 787 59.28948 1352.288 787 62.11417 1346.45 787 64.3656 1340.367 787 66.02297 1334.097 787 67.07099 1327.696 787 67.07099 1312.304 787 63.1379 1307.441 787 61.60289 1301.313 787 64.06488 1313.69 787 64.37485 1320 787 -64.06488 1313.69 787 -63.1379 1307.441 787 -61.60289 1301.313 787 59.4746 1295.365 787 64.06488 1326.31 787 -64.37485 1320 787 -64.06488 1326.31 787 -59.4746 1295.365 787 61.60289 1338.687 787 59.4746 1344.635 787 -61.60289 1338.687 787 -59.4746 1344.635 787 -63.1379 1332.559 787 63.1379 1332.559 787 56.77355 1350.346 787 53.52573 1355.765 787 49.76243 1360.839 787 -53.52573 1355.765 787 -49.76243 1360.839 787 -56.77354 1350.346 787 45.51989 1365.52 787 40.83897 1369.762 787 35.76475 1373.526 787 12.55891 1383.138 787 18.68703 1381.603 787 6.309839 1384.065 787 -12.55891 1383.138 787 -6.309838 1384.065 787 -18.68703 1381.603 787 -40.83897 1369.762 787 -35.76475 1373.526 787 -45.51989 1365.52 787 30.34609 1376.774 787 24.63519 1379.475 787 2.41832e-7 1384.375 787 -24.63519 1379.475 787 -30.34609 1376.774 787 40.83897 1270.238 787 45.51989 1274.48 787 -6.309838 1255.935 787 2.41832e-7 1255.625 787 18.68703 1258.397 787 24.63519 1260.525 787 35.76475 1266.474 787 49.76243 1279.161 787 53.52573 1284.235 787 56.77355 1289.654 787 -56.77354 1289.654 787 -53.52573 1284.235 787 -24.63519 1260.525 787 -18.68703 1258.397 787 -12.55891 1256.862 787 30.34609 1263.226 787 -45.51989 1274.48 787 -40.83897 1270.238 787 -35.76475 1266.474 787 -30.34609 1263.226 787 -49.76243 1279.161 787 12.55891 1256.862 787 6.309839 1255.935 838.5845 -50.8107 1295.974 836.8328 -52.56242 1299.255 840.5643 -48.83039 1292.82 834.7329 -54.66234 1304.414 833.2341 -56.16111 1309.808 832.5025 -56.89268 1314.397 832.1755 -57.21971 1318.596 832.3674 -57.02779 1324.639 833.234 -56.16117 1330.192 834.2006 -55.19457 1333.822 799.5 -57.66555 1343.832 835.5521 -53.84331 1337.741 818.1085 -55.76547 1340.615 799.5 -55.02751 1349.413 799.5 -51.87958 1354.665 799.5 -48.23202 1359.583 799.5 -44.11996 1364.12 799.5 -39.583 1368.232 799.5 -34.66482 1371.88 799.5 -29.41282 1375.027 799.5 -23.83198 1377.665 800.687 -19.05084 1379.222 803.9943 -23.04322 1377.217 798.2008 -15.20453 1380.726 796.1968 -11.21657 1381.941 794.6897 -6.19046 1382.853 794.0076 -1.51945 1383.265 794.4109 5.120536 1383.023 796.1932 11.21554 1381.942 799.2864 17.11111 1380.068 803.589 22.67752 1377.463 808.9617 27.807 1374.209 815.273 32.43731 1370.387 820.0142 35.2219 1367.515 825.0573 37.78218 1364.46 836.6261 39.45495 1360.487 842.9443 40.16556 1358.322 850.1348 41.67736 1354.949 860.5864 43.34885 1350.046 872.0291 44.53184 1344.675 867.277 44.0994 1346.908 872.4405 46.0005 1341.656 871.9635 46.67584 1340.347 871.0313 46 1342.174 868.0929 48.90857 1336.298 867.833 49.35148 1334.971 867.0531 50.70237 1330.085 866.5803 51.52128 1325.074 866.4218 51.79566 1320 866.5803 51.52128 1314.926 867.0531 50.70237 1309.915 860.6814 45.2099 1292.91 867.277 44.0994 1293.092 862.2946 43.53998 1290.755 872.0287 44.52843 1295.325 871.0313 46 1297.826 857.7831 47.47136 1296.043 872.4406 46.00048 1298.343 853.7771 49.75831 1299.534 871.9686 46.67395 1299.636 799.5 57.66785 1296.171 867.833 49.35148 1305.029 849.6619 51.62242 1302.635 868.0949 48.90812 1303.716 799.5 55.02751 1290.587 799.5 51.87958 1285.335 799.5 48.23202 1280.417 799.5 44.11996 1275.88 799.5 39.583 1271.768 799.5 34.66483 1268.12 799.5 29.41282 1264.973 799.5 23.83207 1262.335 800.7362 19.11796 1260.807 804.1541 23.21487 1262.879 798.2008 15.20453 1259.274 796.1968 11.21656 1258.059 794.6897 6.19046 1257.147 794.0092 1.548086 1256.735 794.4076 -5.104154 1256.974 796.1934 -11.21553 1258.058 799.2866 -17.11147 1259.932 803.5893 -22.67784 1262.537 808.9614 -27.80673 1265.791 815.2728 -32.43724 1269.613 820.0142 -35.2219 1272.485 825.0576 -37.76333 1275.541 836.6249 -39.4549 1279.513 842.9443 -40.16556 1281.678 850.1339 -41.6772 1285.051 860.8942 -43.39003 1290.098 847.3952 -46 1290.2 862.8542 -45.99934 1294.975 868.1292 -44.1835 1293.492 876.1397 -44.8099 1297.251 902.0032 -41.525 1299.84 899.1919 -41.93821 1299.671 903.2298 -40.48775 1298.238 900.7331 -42.6075 1301.755 895.6437 -43.01625 1300.651 876.7388 -46.00049 1299.963 885.6746 -44.3686 1299.807 898.6227 -44.45021 1305.691 892.9683 -46.00008 1307.745 885.6724 -45.99995 1303.851 899.5252 -43.65333 1303.828 897.6271 -45.30984 1308.073 896.8518 -45.99617 1310.421 825.0905 30.67441 1275.56 849.662 33.81697 1284.829 842.9443 32.34099 1281.678 847.3952 -46 1342.33 840.5668 -48.82843 1341.379 868.9731 48.40236 1312.229 870.1884 47.70069 1305.545 870.4633 47.54194 1335.415 869.445 48.12987 1330.851 868.5 48.67539 1318.441 868.6577 48.58435 1324.668 985.205 46 1350.355 985.215 46 1347.084 982.1917 46 1352.531 987.9731 46 1344.66 987.6718 46 1341.359 973.6946 46 1365.385 974.5748 46 1362.371 970.0594 46 1366.664 978.0295 46 1360.77 978.6327 46 1357.645 981.8793 46 1355.743 952.4431 46 1378.867 954.2529 46 1376.516 948.4108 46 1378.68 958.2386 46 1376.317 959.8461 46 1373.772 963.7489 46 1373.198 965.133 46 1370.477 968.9183 46 1369.542 991.7305 46 1332.584 990.7908 46 1329.313 989.5368 46 1335.415 992.6818 46 1326.324 991.4211 46 1323.115 990.1556 46 1338.716 993 46 1320 992.6818 46 1313.676 991.4211 46 1316.885 991.7305 46 1307.416 990.7908 46 1310.687 990.1556 46 1301.284 989.5368 46 1304.585 987.9731 46 1295.34 987.6718 46 1298.641 985.205 46 1289.645 985.215 46 1292.916 978.0295 46 1279.23 973.6946 46 1274.615 974.5748 46 1277.629 968.9183 46 1270.458 970.0594 46 1273.336 981.8793 46 1284.257 978.6327 46 1282.355 963.7489 46 1266.802 965.133 46 1269.523 958.2386 46 1263.683 959.8461 46 1266.228 952.4431 46 1261.133 954.2529 46 1263.484 946.4208 46 1259.178 948.4108 46 1261.32 872.6525 46 1346.082 982.1917 46 1287.469 940.2327 46 1257.837 942.3799 46 1259.759 933.9412 46 1257.123 936.2219 46 1258.816 874.785 46 1347.084 875.5601 46 1351.706 877.8084 46 1352.531 903.1583 46 1376.996 905.7471 46 1376.516 900.1539 46 1373.772 909.015 46 1379.402 911.5892 46 1378.68 874.785 46 1292.916 872.6525 46 1293.918 879.0177 46 1357.011 881.3673 46 1357.645 882.9902 46 1361.941 885.4252 46 1362.371 887.4376 46 1366.448 889.9406 46 1366.664 897.5728 46 1374.014 894.867 46 1370.477 940.2327 46 1382.163 942.3799 46 1380.241 936.2219 46 1381.184 946.4208 46 1380.822 909.015 46 1260.598 903.1583 46 1263.004 905.7471 46 1263.484 897.5728 46 1265.986 900.1539 46 1266.228 875.5601 46 1288.294 892.3148 46 1370.486 927.61 46 1382.955 930 46 1381.5 923.7781 46 1381.184 933.9412 46 1382.877 892.3148 46 1269.514 894.867 46 1269.523 887.4376 46 1273.552 882.9902 46 1278.059 885.4252 46 1277.629 879.0177 46 1282.989 881.3673 46 1282.355 877.8084 46 1287.469 915.0836 46 1381.209 917.6201 46 1380.241 921.3029 46 1382.397 927.61 46 1257.045 930 46 1258.5 921.3029 46 1257.603 923.7781 46 1258.816 889.9406 46 1273.336 915.0836 46 1258.791 917.6201 46 1259.759 911.5892 46 1261.32 876.1647 21.55134 1297.261 872.04 30.48681 1295.327 876.749 30.48855 1286.338 873.7131 30.5 1291.702 880.3894 30.50011 1281.169 884.4883 30.51804 1276.437 889.0197 30.51715 1272.15 893.9356 30.51981 1268.344 899.2254 30.50001 1265.028 904.8288 30.5148 1262.247 910.6701 30.51405 1260.038 916.6797 30.51604 1258.424 922.8399 30.50005 1257.408 929.0816 30.51175 1257.007 935.3165 30.51091 1257.224 941.4987 30.51013 1258.058 947.5707 30.50959 1259.5 953.4686 30.50864 1261.534 959.1377 30.50803 1264.143 964.5194 30.50723 1267.299 969.5584 30.5079 1270.968 974.2169 30.49998 1275.124 978.4439 30.50518 1279.724 982.19 30.50448 1284.712 985.4227 30.50448 1290.045 988.1143 30.5 1295.674 990.2372 30.50223 1301.547 991.7669 30.50146 1307.596 992.6911 30.50081 1313.768 993 30.5 1320 992.6911 30.5008 1326.233 991.7669 30.50152 1332.404 990.2365 30.50004 1338.455 988.1148 30.50355 1344.325 985.4246 30.50376 1349.952 982.1899 30.50444 1355.288 978.4406 30.50004 1360.28 974.2159 30.50727 1364.877 969.5646 30.50669 1369.027 964.5205 30.50722 1372.701 959.1377 30.50793 1375.857 953.468 30.5089 1378.466 947.5706 30.50938 1380.5 941.4976 30.50994 1381.942 935.3137 30.5107 1382.775 929.0673 30.49998 1382.993 922.8399 30.51539 1382.592 916.6962 30.51328 1381.58 910.671 30.51404 1379.962 904.8111 30.49989 1377.745 899.2254 30.51862 1374.972 893.9515 30.51644 1371.668 889.0197 30.51699 1367.85 884.4736 30.5 1363.547 880.3889 30.50031 1358.83 876.7496 30.48871 1353.664 873.7131 30.5 1348.298 872.0401 30.48664 1344.673 895.6259 -15.73717 1300.652 885.6718 2.456566 1299.806 842.9443 -31.2318 1358.322 876.1638 21.55319 1342.739 876.5396 -37.67366 1342.625 876.8862 -46 1334.223 825.0905 -30.02105 1364.44 895.9806 -46 1314.262 896.4398 -46 1327.998 896.8781 -45.99814 1329.645 889.4898 -45.99971 1334.224 895.6733 -46 1323.453 895.5193 -46 1318.847 899.9349 -43.29876 1336.924 898.9179 -44.18093 1334.972 898.1001 -44.8928 1333.144 897.2962 -45.60078 1330.987 885.6718 2.456566 1340.194 885.6718 -40.02923 1340.194 895.6437 -40.87447 1339.348 895.6257 -15.73711 1339.347 898.3141 -19.50238 1340.08 900.4816 -19.50265 1343.14 903.4012 -19.5025 1346.476 905.4946 -19.50155 1348.398 907.7426 -19.50127 1350.205 911.5336 -19.50202 1352.652 909.9284 -19.50097 1351.691 915.648 -19.50241 1354.677 918.3062 -19.50153 1355.64 921.1026 -19.5011 1356.45 925.4946 -19.50247 1357.239 923.5818 -19.50099 1356.96 930.1025 -19.50234 1357.53 932.9105 -19.50139 1357.397 936.9503 -19.5015 1356.864 935.0588 -19.50137 1357.17 939.6748 -19.50139 1356.251 943.3192 -19.50063 1355.08 946.5781 -19.50183 1353.656 949.8998 -19.50057 1351.813 952.8842 -19.50142 1349.733 956.4031 -19.50087 1346.654 955.0991 -19.50102 1347.878 959.366 -19.50253 1343.37 961.0633 -19.50155 1341.027 962.5721 -19.5014 1338.622 964.6074 -19.50127 1334.483 963.8664 -19.50101 1336.131 966.1015 -19.50253 1330.255 966.7605 -19.50156 1327.461 967.2328 -19.50135 1324.628 967.4622 -19.50099 1321.931 967.512 -19.50164 1320.054 967.242 -19.50179 1315.435 966.0803 -19.50179 1309.667 966.7604 -19.50156 1312.539 965.3426 -19.501 1307.427 964.664 -19.50209 1305.665 962.7027 -19.50218 1301.595 960.5711 -19.50052 1298.242 958.1914 -19.50129 1295.247 956.5076 -19.50257 1293.46 953.0941 -19.5021 1290.421 949.8991 -19.50057 1288.186 946.5772 -19.50182 1286.344 941.9663 -19.50102 1284.448 944.0683 -19.50132 1285.223 939.67 -19.50151 1283.748 935.057 -19.50136 1282.83 936.9508 -19.50151 1283.136 932.3339 -19.50172 1282.555 927.4456 -19.50101 1282.575 929.6143 -19.5013 1282.485 925.563 -19.50082 1282.751 922.0664 -19.5 1283.325 920.4264 -19.50119 1283.728 915.6089 -19.50201 1285.34 918.304 -19.50155 1284.361 913.2932 -19.50101 1286.414 911.6351 -19.50122 1287.291 907.936 -19.50222 1289.646 903.3545 -19.50191 1293.571 905.4949 -19.50154 1291.602 901.7026 -19.50099 1295.374 900.4866 -19.50215 1296.853 898.3141 -19.50237 1299.92 899.1919 -39.89443 1340.328 901.8429 -40.30261 1339.924 901.8276 -38.95847 1341.265 903.2297 -38.99188 1341.762 903.2297 -33.5 1341.762 902.2733 -33.49997 1341.422 905.4741 -33.5 1345.014 908.9336 -33.5 1347.989 912.7505 -33.5 1350.49 916.8601 -33.5 1352.474 921.1926 -33.5 1353.906 925.6746 -33.5 1354.763 930.2299 -33.5 1355.031 934.7814 -33.5 1354.704 939.2518 -33.5 1353.788 943.5651 -33.5 1352.298 947.6483 -33.5 1350.261 951.432 -33.5 1347.71 954.8521 -33.5 1344.69 957.8505 -33.5 1341.25 960.3764 -33.5 1337.449 962.3868 -33.5 1333.353 963.8477 -33.5 1329.03 964.7343 -33.5 1324.553 965.0314 -33.5 1320 964.7343 -33.5 1315.447 963.8477 -33.5 1310.97 962.3868 -33.5 1306.647 960.3764 -33.5 1302.551 957.8505 -33.5 1298.75 954.8521 -33.5 1295.31 951.4321 -33.5 1292.29 947.6483 -33.5 1289.739 943.5651 -33.5 1287.702 939.2518 -33.5 1286.212 934.7814 -33.5 1285.296 930.2299 -33.5 1284.969 925.6746 -33.5 1285.237 921.1926 -33.5 1286.094 916.8601 -33.5 1287.526 912.7505 -33.5 1289.51 908.9336 -33.5 1292.011 905.4741 -33.5 1294.986 902.2728 -33.50001 1298.578 903.1971 -33.49999 1298.243 951.3814 -33.5 1347.076 947.5818 -33.5 1349.684 959.0798 -33.5 1301.436 961.2946 -33.5 1305.478 964.0194 -33.5 1314.262 964.4807 -33.5 1318.847 964.3267 -33.5 1323.453 963.5602 -33.5 1327.998 954.7994 -33.5 1343.984 956.346 -33.5 1297.726 957.7749 -33.5 1340.465 905.2006 -33.5 1343.984 941.3168 -33.5 1287.409 945.5599 -33.5 1289.208 949.5252 -33.5 1291.557 953.1421 -33.5 1294.413 962.9511 -33.5 1309.778 962.1948 -33.5 1332.4 960.2548 -33.5 1336.58 943.4685 -33.5 1351.762 908.6187 -33.5 1347.076 936.872 -33.5 1286.191 939.1148 -33.5 1353.274 934.5984 -33.5 1354.192 930 -33.5 1354.5 920.8853 -33.5 1353.274 925.4016 -33.5 1354.192 916.5316 -33.5 1351.762 912.4182 -33.5 1349.684 906.8579 -33.5 1294.413 923.1281 -33.5 1286.191 918.6832 -33.5 1287.409 927.6957 -33.5 1285.577 932.3043 -33.5 1285.577 910.4749 -33.5 1291.557 914.4401 -33.5 1289.208 926.5478 -46.5 1354.327 922.0023 -46.5 1353.56 917.601 -46.5 1352.195 913.4212 -46.5 1350.256 909.5372 -46.5 1347.776 906.0134 -46.5 1344.797 906.0164 -46.5 1295.201 909.5361 -46.5 1292.224 913.4218 -46.5 1289.744 917.6005 -46.5 1287.805 922.0039 -46.5 1286.44 926.5453 -46.5 1285.673 931.1511 -46.5 1285.519 935.7376 -46.5 1285.981 940.2201 -46.5 1287.049 944.5208 -46.5 1288.704 948.5645 -46.5 1290.92 952.273 -46.5 1293.653 955.587 -46.5 1296.858 958.4432 -46.5 1300.475 960.7919 -46.5 1304.44 962.591 -46.5 1308.683 963.8088 -46.5 1313.128 964.423 -46.5 1317.696 964.423 -46.5 1322.304 963.8087 -46.5 1326.873 962.5913 -46.5 1331.317 960.7915 -46.5 1335.561 958.4432 -46.5 1339.525 955.5858 -46.5 1343.143 952.2742 -46.5 1346.346 948.5648 -46.5 1349.079 944.5245 -46.5 1351.294 940.2208 -46.5 1352.951 935.736 -46.5 1354.02 931.1546 -46.5 1354.481 902.8294 -46.50003 1341.244 900.3263 -46.49999 1337.593 898.2343 -46.50006 1333.449 896.726 -46.5 1329.116 895.8078 -46.5 1324.598 895.5001 -46.5 1320 895.8078 -46.5 1315.402 896.7358 -46.49993 1310.856 898.2861 -46.49985 1306.454 900.3425 -46.49993 1302.396 903.6968 -46.5 1297.765 902.9244 -46.5 1298.619 923.7781 61 1258.816 930 61 1258.5 917.6201 61 1259.759 911.5892 61 1261.32 905.7471 61 1263.484 900.1539 61 1266.228 894.867 61 1269.523 889.9406 61 1273.336 885.4252 61 1277.629 881.3673 61 1282.355 877.8084 61 1287.469 874.785 61 1292.916 877.8084 61 1352.531 874.785 61 1347.084 881.3673 61 1357.645 885.4252 61 1362.371 889.9406 61 1366.664 894.867 61 1370.477 900.1539 61 1373.772 905.7471 61 1376.516 911.5892 61 1378.68 917.6201 61 1380.241 923.7781 61 1381.184 930 61 1381.5 936.2219 61 1381.184 942.3799 61 1380.241 948.4108 61 1378.68 954.2529 61 1376.516 959.8461 61 1373.772 965.133 61 1370.477 970.0594 61 1366.664 974.5748 61 1362.371 978.6327 61 1357.645 982.1917 61 1352.531 985.215 61 1347.084 987.6718 61 1341.359 989.5368 61 1335.415 990.7908 61 1329.313 991.4211 61 1323.115 991.4211 61 1316.885 990.7908 61 1310.687 989.5368 61 1304.585 987.6718 61 1298.641 985.215 61 1292.916 982.1917 61 1287.469 978.6327 61 1282.355 974.5748 61 1277.629 970.0594 61 1273.336 965.133 61 1269.523 959.8461 61 1266.228 954.2529 61 1263.484 948.4108 61 1261.32 942.3799 61 1259.759 936.2219 61 1258.816 872.3283 61 1298.641 869.2092 61 1310.687 870.4633 61 1304.585 868.5789 61 1316.885 868.5789 61 1323.115 869.2092 61 1329.313 870.4633 61 1335.415 872.3283 61 1341.359 956.9692 61 1276.126 879.4553 61 1329.873 878.6759 61 1324.253 880.8482 61 1335.374 882.8377 61 1340.687 885.3997 61 1345.75 888.5031 61 1350.5 900.6549 61 1362.322 905.4887 61 1365.293 974.6004 61 1345.75 971.4969 61 1350.5 977.1624 61 1340.687 979.1519 61 1335.374 980.5447 61 1329.873 981.3241 61 1324.253 975.9511 61 1296.746 978.2304 61 1301.942 973.1141 61 1291.832 969.7537 61 1287.26 965.9108 61 1283.086 961.632 61 1279.359 941.2621 61 1269.746 935.6654 61 1268.813 892.1102 61 1354.88 896.1773 61 1358.837 910.6201 61 1367.714 915.9867 61 1369.557 967.8898 61 1354.88 981.4805 61 1318.581 981.0119 61 1312.926 979.9241 61 1307.358 951.979 61 1273.426 930 61 1268.5 884.0489 61 1296.746 881.7697 61 1301.942 880.0759 61 1307.358 878.9881 61 1312.926 878.5195 61 1318.581 946.7221 61 1271.29 918.7379 61 1269.746 924.3346 61 1268.813 913.278 61 1271.29 898.3681 61 1279.359 903.0308 61 1276.126 894.0892 61 1283.086 890.2463 61 1287.26 886.8859 61 1291.832 927.163 61 1371.422 921.5234 61 1370.798 930 61 1371.5 963.8228 61 1358.837 959.3451 61 1362.322 908.021 61 1273.426 932.837 61 1371.422 938.4766 61 1370.798 949.38 61 1367.714 954.5113 61 1365.293 944.0133 61 1369.557 922.9272 70 1268.988 928.5816 70 1268.52 917.3583 70 1270.076 911.945 70 1271.769 906.7473 70 1274.048 901.8325 70 1276.886 897.2611 70 1280.245 893.0846 70 1284.09 889.3587 70 1288.369 886.1258 70 1293.032 883.4255 70 1298.021 881.2903 70 1303.278 879.7467 70 1308.737 878.8126 70 1314.335 878.8125 70 1325.664 878.5 70 1320 881.2902 70 1336.722 879.7465 70 1331.262 883.4257 70 1341.979 886.1262 70 1346.969 889.3587 70 1351.631 893.0869 70 1355.912 897.2625 70 1359.756 901.833 70 1363.114 906.7468 70 1365.952 911.9399 70 1368.229 917.3559 70 1369.924 922.9267 70 1371.012 928.5801 70 1371.48 934.254 70 1371.324 939.8756 70 1370.545 945.3726 70 1369.152 950.6844 70 1367.163 955.7479 70 1364.601 960.5007 70 1361.496 964.8807 70 1357.889 968.8373 70 1353.822 972.3216 70 1349.345 975.293 70 1344.511 977.7147 70 1339.38 979.5569 70 1334.013 980.7976 70 1328.477 981.4218 70 1322.837 980.7976 70 1311.523 981.4218 70 1317.163 979.557 70 1305.987 977.7149 70 1300.621 975.293 70 1295.489 972.3218 70 1290.656 968.8364 70 1286.177 964.8789 70 1282.109 960.4991 70 1278.502 955.7512 70 1275.401 950.6892 70 1272.839 945.3753 70 1270.848 939.8743 70 1269.455 934.2522 70 1268.676 824.8999 13.03425 1364.534 825.8228 11.68382 1364.189 825.8228 -11.68382 1364.189 824.9 -13.03409 1364.534 803.5326 -13.36396 1377.497 805.9989 -15.95681 1376.002 808.5163 -17.7915 1374.48 811.7516 -19.31781 1372.522 813.9329 -19.90014 1371.198 810.8562 18.94706 1373.061 802.0723 -11.22737 1378.381 813.9328 19.90022 1371.198 799.7788 -5.921096 1379.77 812.346 19.49251 1372.159 799.1236 -2.518902 1380.168 801.0886 -9.425409 1378.977 808.7288 17.91301 1374.348 806.0106 15.95891 1375.996 803.8624 13.76752 1377.297 802.7095 12.22765 1377.995 798.9995 0.9152535 1380.241 801.4055 10.05357 1378.785 800.2897 7.512041 1379.461 799.4197 4.383176 1379.989 822.2865 15.69409 1366.139 817.035 18.92473 1369.319 822.2865 -15.69409 1366.139 819.8553 17.47877 1367.611 819.8553 -17.47877 1367.611 817.035 -18.92473 1369.319 824.6216 13.08001 1365.621 823.0476 14.34642 1367.497 821.3543 15.159 1369.515 819.5952 15.49204 1371.611 817.8261 15.335 1373.719 816.1027 14.69286 1375.773 815.7082 17.21374 1373.132 814.4798 13.58593 1377.707 814.1353 16.55561 1375.024 813.0086 12.04922 1379.461 812.3529 15.33544 1377.152 811.7357 10.13135 1380.978 810.6765 13.59241 1379.144 810.7012 7.892979 1382.211 808.8555 10.62685 1381.299 809.2306 11.43862 1380.852 809.9381 5.404926 1383.12 808.0761 8.900459 1382.246 809.4703 2.745895 1383.677 806.9775 4.831334 1383.537 807.2011 6.102336 1383.27 809.3127 0 1383.865 806.6846 3.140261 1383.895 806.495 0 1384.112 806.6648 -2.99337 1383.91 809.4703 -2.745895 1383.677 806.9775 -4.831334 1383.537 809.9381 -5.404926 1383.12 807.2011 -6.102336 1383.27 807.742 -7.865647 1382.626 810.7012 -7.892979 1382.211 808.0628 -8.911429 1382.244 809.2709 -11.46681 1380.829 811.7357 -10.13135 1380.978 810.7034 -13.62364 1379.116 813.0086 -12.04922 1379.461 812.3363 -15.32786 1377.165 814.4798 -13.58593 1377.707 814.1568 -16.5768 1374.99 816.1027 -14.69286 1375.773 817.8261 -15.335 1373.719 815.7089 -17.21409 1373.131 819.5952 -15.49204 1371.611 821.3543 -15.159 1369.515 823.0476 -14.34642 1367.497 824.6216 -13.08001 1365.621 814.3198 16.87211 1373.897 812.986 16.41505 1374.622 811.6965 15.84737 1375.322 810.3839 15.11998 1376.038 809.0106 14.17217 1376.78 807.9598 13.29274 1377.35 806.9171 12.26609 1377.915 805.8551 11.01473 1378.493 804.8623 9.554981 1379.035 804.1955 8.362166 1379.4 803.5545 6.989064 1379.744 803.0851 5.6918 1380.004 802.6119 3.968091 1380.257 802.3527 2.518067 1380.398 802.211 1.108393 1380.469 802.1818 -0.3747593 1380.488 802.2683 -1.806506 1380.441 802.4543 -3.196168 1380.337 802.78 -4.678852 1380.162 803.1657 -5.936172 1379.955 803.6322 -7.169491 1379.704 804.2761 -8.523912 1379.353 805.3078 -10.25881 1378.789 806.4094 -11.69867 1378.186 807.4094 -12.76729 1377.651 808.8025 -14.04783 1376.884 810.4886 -15.18345 1375.978 811.7504 -15.8748 1375.291 813.0747 -16.45198 1374.572 814.283 -16.85913 1373.919 818.0714 9.822874 1373.427 821.2622 -9.510565 1369.624 819.6795 -9.980268 1371.511 816.5391 9.048272 1375.253 822.7201 -8.443281 1367.887 823.9616 -6.845471 1366.407 815.1786 7.705132 1376.875 814.0756 5.877852 1378.189 813.2994 3.681246 1379.114 815.1786 -7.705132 1376.875 816.5391 -9.048272 1375.253 818.0714 -9.822874 1373.427 824.9087 -4.817537 1365.279 812.8987 1.253332 1379.592 814.0756 -5.877852 1378.189 813.2994 -3.681246 1379.114 812.8987 -1.253332 1379.592 822.7201 8.443281 1367.887 823.9616 6.845471 1366.407 819.6795 9.980268 1371.511 821.2622 9.510565 1369.624 825.7038 0 1364.331 825.5018 -2.486899 1364.572 824.9087 4.817537 1365.279 825.5018 2.486899 1364.572 829.534 0 1367.545 829.332 -2.486899 1367.786 828.7389 -4.817537 1368.493 826.5504 -8.443281 1371.101 825.0924 -9.510565 1372.838 823.5097 -9.980268 1374.725 821.9017 -9.822874 1376.641 820.3693 -9.048272 1378.467 819.0089 -7.705132 1380.088 817.9058 -5.877852 1381.403 817.1296 -3.681246 1382.328 816.729 -1.253332 1382.806 816.6808 0.81158 1382.863 817.1296 3.681246 1382.328 817.9058 5.877852 1381.403 819.0089 7.705132 1380.088 820.3693 9.048272 1378.467 821.9017 9.822874 1376.641 823.5097 9.980268 1374.725 825.0924 9.510565 1372.838 826.5504 8.443281 1371.101 828.7389 4.817537 1368.493 829.332 2.486899 1367.786 827.7918 6.845471 1369.621 827.7918 -6.845471 1369.621 824.8999 -13.03423 1275.466 825.8228 11.68382 1275.811 824.8999 13.03424 1275.466 825.8228 -11.68382 1275.811 803.5321 13.36323 1262.503 805.9992 15.95701 1263.998 808.0147 17.45754 1265.218 809.7877 18.46235 1266.291 811.7523 19.318 1267.479 813.9329 19.90019 1268.802 810.8563 -18.94711 1266.939 802.0723 11.22736 1261.619 813.9329 -19.90021 1268.802 799.7786 5.92041 1260.23 812.3461 -19.49243 1267.841 799.1235 2.517426 1259.832 801.0889 9.426149 1261.024 808.7291 -17.91311 1265.652 806.0103 -15.95861 1264.004 803.8673 -13.77324 1262.706 802.7141 -12.23474 1262.007 798.9993 -0.9151 1259.759 801.4059 -10.05425 1261.215 800.2899 -7.512141 1260.539 799.4196 -4.383019 1260.012 822.2865 -15.69409 1273.861 822.2865 15.69409 1273.861 819.8553 -17.47877 1272.389 817.035 -18.92473 1270.681 819.8553 17.47877 1272.389 817.035 18.92473 1270.681 824.6216 -13.08001 1274.379 823.0476 -14.34642 1272.503 821.3543 -15.159 1270.485 819.5952 -15.49204 1268.389 817.8261 -15.335 1266.281 816.1027 -14.69286 1264.227 815.7081 -17.21375 1266.868 814.4798 -13.58593 1262.293 814.1354 -16.55563 1264.976 813.0086 -12.04922 1260.539 812.3529 -15.33546 1262.848 811.7357 -10.13135 1259.022 810.6764 -13.59237 1260.856 810.7012 -7.892979 1257.789 808.8555 -10.62685 1258.701 809.2306 -11.43862 1259.148 809.9381 -5.404926 1256.88 808.0762 -8.900295 1257.754 809.4703 -2.745895 1256.322 806.9775 -4.831334 1256.463 807.2011 -6.102336 1256.73 809.3127 0 1256.135 806.6847 -3.140017 1256.105 806.495 0 1255.888 806.6649 2.993065 1256.09 809.4703 2.745895 1256.322 806.9775 4.831334 1256.463 809.9381 5.404926 1256.88 807.2011 6.102336 1256.73 807.742 7.865647 1257.374 810.7012 7.892979 1257.789 808.0628 8.911429 1257.756 809.2514 11.45354 1259.16 811.7357 10.13135 1259.022 810.7033 13.62337 1260.884 813.0086 12.04922 1260.539 812.3364 15.32798 1262.835 814.4798 13.58593 1262.293 814.1566 16.57671 1265.01 816.1027 14.69286 1264.227 817.8261 15.335 1266.281 815.7088 17.2141 1266.869 819.5952 15.49204 1268.389 821.3543 15.159 1270.485 823.0476 14.34642 1272.503 824.6216 13.08001 1274.379 814.283 16.85916 1266.081 813.0743 16.45185 1265.428 811.7503 15.87482 1264.709 810.4888 15.18357 1264.023 808.8028 14.04795 1263.116 807.408 12.76599 1262.348 806.3094 11.58352 1261.762 805.3078 10.25872 1261.211 804.2764 8.524503 1260.647 803.6327 7.170562 1260.297 803.1657 5.936173 1260.045 802.7801 4.67912 1259.838 802.4541 3.195395 1259.663 802.2683 1.805464 1259.559 802.1818 0.3746267 1259.512 802.2109 -1.107646 1259.531 802.3527 -2.518501 1259.602 802.6119 -3.968333 1259.743 803.085 -5.691137 1259.996 803.5541 -6.987759 1260.256 804.2089 -8.385049 1260.607 804.8621 -9.554759 1260.965 805.8395 -10.99297 1261.497 806.9168 -12.26582 1262.085 807.9598 -13.29278 1262.651 809.0101 -14.17183 1263.22 810.3836 -15.11979 1263.962 811.6969 -15.84758 1264.679 812.9862 -16.41508 1265.378 814.3198 -16.87213 1266.104 823.3732 7.705132 1272.891 822.0128 9.048272 1271.27 815.8317 8.443281 1263.904 814.5902 6.845471 1262.424 820.4804 9.822874 1269.444 822.0128 -9.048272 1271.27 813.6431 4.817537 1261.295 817.2896 9.510565 1265.641 818.8723 9.980268 1267.527 823.3732 -7.705132 1272.891 820.4804 -9.822874 1269.444 818.8723 -9.980268 1267.527 814.5902 -6.845471 1262.424 813.05 2.486899 1260.589 824.4761 5.877852 1274.206 817.2896 -9.510565 1265.641 815.8317 -8.443281 1263.904 813.05 -2.486899 1260.589 813.6431 -4.817537 1261.295 825.6531 1.253332 1275.608 825.2524 3.681246 1275.131 812.848 0 1260.348 824.4761 -5.877852 1274.206 825.2524 -3.681246 1275.131 825.6531 -1.253332 1275.608 816.6782 0 1257.134 816.8802 -2.486899 1257.375 817.4733 -4.817537 1258.082 818.4204 -6.845471 1259.21 821.1198 -9.510565 1262.427 824.3106 -9.822874 1266.23 825.843 -9.048272 1268.056 828.3064 -5.877852 1270.992 829.0826 -3.681246 1271.917 829.4833 -1.253332 1272.394 829.5319 0.8058906 1272.452 829.0826 3.681246 1271.917 828.3064 5.877852 1270.992 825.843 9.048272 1268.056 824.3106 9.822874 1266.23 821.1198 9.510565 1262.427 818.4204 6.845471 1259.21 817.4733 4.817537 1258.082 816.8802 2.486899 1257.375 819.6619 8.443281 1260.69 822.7025 9.980268 1264.313 827.2034 7.705132 1269.677 827.2034 -7.705132 1269.677 822.7025 -9.980268 1264.313 819.6619 -8.443281 1260.69 + + + + + + + + + + -1 -7.3064e-5 0 -1 -2.97199e-5 0 -1 0 0 -1 1.84689e-5 0 -1 1.10661e-5 0 -1 -7.3373e-5 0 -1 -1.91217e-5 0 -1 -7.25234e-6 0 -1 -1.72266e-5 0 -1 4.28481e-6 0 -1 -3.18721e-6 0 -1 1.29128e-5 0 -1 -1.0328e-5 0 -1 -3.12076e-6 0 -1 -3.61322e-6 0 -1 -3.09839e-5 0 -1 2.18543e-4 0 -1 -1.01007e-5 0 -1 4.28064e-5 0 -1 6.47122e-6 0 -1 -1.51183e-5 0 -1 3.42812e-5 0 -1 -1.49858e-5 0 -1 -5.05043e-6 0 -1 -7.08377e-6 0 -1 -6.1983e-6 0 -1 2.49667e-5 0 -1 -1.65893e-5 0 -1 -4.61146e-7 0 -1 3.11054e-5 0 -1 -2.6901e-6 0 -1 8.74532e-6 0 -1 1.49275e-5 0 -1 9.27455e-6 0 -1 9.12722e-6 0 -1 -1.52015e-5 0 -1 3.17194e-6 0 -1 -4.5353e-7 0 -1 -2.10349e-5 0 -1 -1.45801e-5 0 -1 -3.30611e-6 0 0 -0.04550695 0.998964 0 -0.136104 0.9906946 0 -0.2257056 0.9741957 0 -0.3134357 0.9496095 0 -0.3983413 0.9172373 0 -0.4802042 0.8771567 0 -0.5578682 0.8299295 0 -0.6311312 0.7756761 0 -0.6989753 0.7151458 0 -0.7611391 0.6485888 0 -0.8170026 0.5766341 0 -0.8660156 0.500017 0 -0.9079121 0.4191607 0 -0.9422523 0.3349037 0 -0.9688122 0.2477959 0 -0.9873287 0.1586893 0 -0.9976688 0.06824362 0 -0.999741 -0.02275973 0 -0.993529 -0.1135792 0 -0.9790809 -0.203472 0 -0.9565312 -0.2916305 0 -0.9260452 -0.3774128 0 -0.8878736 -0.4600877 0 -0.8423572 -0.5389198 0 -0.7899056 -0.6132285 0 -0.7307924 -0.6825999 0 -0.6657922 -0.7461373 0 -0.5950927 -0.8036571 0 -0.5195923 -0.8544144 0 -0.4397142 -0.8981379 0 -0.3562375 -0.9343956 0 -0.269786 -0.9629203 0 -0.1811894 -0.9834483 0 -0.09089237 -0.9958608 0 -0.01327604 -0.9999119 0.001266539 0 -0.9999992 0 0.09089243 -0.9958608 0 0.1811894 -0.9834482 0 0.269786 -0.9629203 0 0.3562375 -0.9343956 0 0.4397142 -0.8981379 0 0.5195923 -0.8544144 0 0.5950927 -0.8036571 0 0.6657916 -0.7461378 0 0.7307924 -0.6825999 0 0.7899051 -0.6132292 0 0.8423572 -0.5389198 0 0.8878731 -0.4600886 0 0.9260444 -0.3774147 0 0.9565317 -0.2916284 0 0.9790809 -0.203472 0 0.993529 -0.1135792 0 0.999741 -0.02275973 0 0.9976689 0.06824129 0 0.9873282 0.1586916 0 0.9688128 0.2477937 0 0.9422531 0.3349017 0 0.9079121 0.4191607 0 0.8660171 0.5000144 0 0.8170026 0.5766341 0 0.7611402 0.6485875 0 0.6989753 0.7151458 0 0.6311306 0.7756766 0 0.5578687 0.8299292 0 0.4802037 0.877157 0 0.3983413 0.9172373 0 0.3134357 0.9496095 0 0.2257055 0.9741957 0 0.1361039 0.9906947 0 0.04550695 0.998964 0 0.1361043 0.9906946 0 0.2257056 0.9741957 0 0.3134363 0.9496093 0 0.4802042 0.8771567 0 0.5578682 0.8299295 0 0.6311312 0.7756761 0 0.6989759 0.7151453 0 0.7611391 0.6485888 0 0.866016 0.5000165 0 0.9079117 0.4191616 0 0.9422523 0.3349037 0 0.9688122 0.2477959 0 0.9873286 0.1586897 0 0.9976687 0.06824374 0 0.9790807 -0.2034724 0 0.9565313 -0.2916298 0 0.9260448 -0.3774136 0 0.8878736 -0.4600877 0 0.7899056 -0.6132285 0 0.6657922 -0.7461373 0 0.5195915 -0.8544149 0 0.1811894 -0.9834483 -5.31222e-4 0.0863291 -0.9962666 0 -0.09089243 -0.9958608 0 -0.1811894 -0.9834482 0 -0.5195915 -0.8544149 0 -0.6657916 -0.7461378 0 -0.7899051 -0.6132292 0 -0.8878731 -0.4600886 0 -0.926044 -0.3774155 0 -0.956532 -0.2916277 0 -0.9790807 -0.2034724 0 -0.9976689 0.06824147 0 -0.9873282 0.158692 0 -0.9688128 0.2477937 0 -0.9422531 0.3349017 0 -0.9079117 0.4191616 0 -0.8660174 0.5000139 0 -0.7611402 0.6485875 0 -0.6989759 0.7151453 0 -0.6311306 0.7756766 0 -0.5578687 0.8299292 0 -0.4802037 0.877157 0 -0.3134363 0.9496093 0 -0.2257055 0.9741957 0 -0.1361042 0.9906945 1 0 0 1 4.35874e-5 0 1 2.61488e-5 0 1 7.1582e-5 0 1 7.1589e-5 0 1 -1.74338e-5 0 1 -1.74319e-5 0 1 -4.35798e-5 0 1 -6.97496e-5 0 1 -1.74331e-5 0 1 -6.97301e-5 0 1 1.78993e-5 0 1 -2.68452e-5 0 1 8.94871e-6 0 1 8.95063e-6 0 1 4.35813e-5 0 1 2.68519e-5 0 1 -8.71703e-6 0 1 1.74389e-5 0 1 7.15896e-5 0 1 -7.15922e-5 0 1 -1.74347e-5 0 1 3.48742e-5 0 1 -6.97399e-5 0 1 2.685e-5 0 1 -2.68485e-5 0 1 6.97277e-5 0 1 -1.78984e-5 0 1 -2.61534e-5 0 1 1.78981e-5 0 1 -1.79e-5 0 1 -6.97277e-5 0 1 -1.74341e-5 0 1 -3.48626e-5 0 1 4.47451e-5 0 1 -3.48657e-5 0 1 1.74307e-5 0 1 3.57987e-5 0 1 4.47435e-5 0 1 3.57884e-5 0 1 1.78977e-5 0 1 -4.47435e-5 0 1 -1.74322e-5 0 1 -3.48772e-5 0 1 6.97253e-5 0 1 1.74319e-5 0 1 -1.79032e-5 0 1 8.94919e-6 0 1 -3.57961e-5 0 1 1.79032e-5 0 1 -1.78949e-5 0 1 1.74325e-5 0 1 8.71688e-6 0 1 1.74392e-5 0 1 -1.78929e-5 0 1 -1.7438e-5 0 1 3.57967e-5 0 1 1.78929e-5 0 1 -1.78974e-5 0 1 1.74386e-5 0 1 3.48651e-5 0 0 -0.04555815 0.9989617 0 -0.1360687 0.9906994 0 -0.2257161 0.9741932 0 -0.3133138 0.9496498 0 -0.3984027 0.9172106 0 -0.4802469 0.8771334 0 -0.5579295 0.8298884 0 -0.6310376 0.7757524 0 -0.6989887 0.7151328 0 -0.7611778 0.6485434 0 -0.81699 0.5766518 0 -0.8660057 0.5000342 0 -0.9079187 0.4191463 0 -0.9422612 0.334879 0 -0.9688076 0.2478142 0 -0.9873272 0.1586977 0 -0.9976693 0.06823569 0 -0.999741 -0.02276343 0 -0.9935286 -0.1135829 0 -0.9790877 -0.2034392 0 -0.9565199 -0.2916674 0 -0.9260382 -0.37743 0 -0.8878928 -0.4600506 0 -0.8423681 -0.5389025 0 -0.7898997 -0.6132361 0 -0.730798 -0.6825938 0 -0.6657233 -0.7461988 0 -0.5951213 -0.8036359 0 -0.5196556 -0.8543758 0 -0.4397247 -0.8981326 0 -0.3562253 -0.9344002 0 -0.2697929 -0.9629184 0 -0.1810551 -0.983473 0 -0.09095549 -0.995855 0 0.02284467 -0.9997391 0 -0.02284467 -0.9997391 0 0.09095549 -0.995855 0 0.1810551 -0.983473 0 0.2697932 -0.9629183 0 0.3562253 -0.9344002 0 0.4397245 -0.8981328 0 0.5196556 -0.8543758 0 0.5951213 -0.8036359 0 0.6657238 -0.7461983 0 0.7307975 -0.6825944 0 0.7898997 -0.6132361 0 0.8423681 -0.5389025 0 0.8878919 -0.4600522 0 0.9260374 -0.3774317 0 0.9565204 -0.2916654 0 0.9790885 -0.2034351 0 0.9935289 -0.1135808 0 0.9997408 -0.02276551 0 0.9976694 0.0682336 0 0.9873269 0.1586998 0 0.9688071 0.2478162 0 0.9422618 0.3348771 0 0.9079196 0.4191446 0 0.8660048 0.5000358 0 0.8169891 0.5766533 0 0.7611774 0.648544 0 0.6989892 0.7151322 0 0.6310376 0.7757524 0 0.55793 0.8298881 0 0.4802477 0.877133 0 0.3984029 0.9172105 0 0.3133141 0.9496496 0 0.2257161 0.9741932 0 0.1360687 0.9906994 0 0.04555815 0.9989617 0 0.3133138 0.9496498 0 0.3984027 0.9172106 0 0.4802501 0.8771317 0 0.5579295 0.8298884 0 0.631035 0.7757543 0 0.6989887 0.7151328 0 0.7611778 0.6485434 0 0.8169887 0.5766538 0 0.8660057 0.5000342 0 0.9079173 0.4191495 0 0.9422603 0.3348816 0 0.9688071 0.2478163 0 0.987327 0.158699 0 0.9976693 0.06823569 0 0.999741 -0.02276343 0 0.9935285 -0.1135838 0 0.9790877 -0.2034392 0 0.9565206 -0.291665 0 0.926037 -0.3774329 0 0.8878928 -0.4600506 0 0.730798 -0.6825938 0 0.6657233 -0.7461988 0 0.5196587 -0.854374 0 0.4397281 -0.898131 0 0.2697929 -0.9629184 0 0.09095549 -0.995855 0 -0.09095549 -0.995855 0 -0.2697932 -0.9629183 0 -0.4397279 -0.8981311 0 -0.5196587 -0.854374 0 -0.6657238 -0.7461983 0 -0.7307975 -0.6825944 0 -0.8878919 -0.4600522 0 -0.9260363 -0.3774347 0 -0.9565212 -0.2916631 0 -0.9790885 -0.2034351 0 -0.9935287 -0.1135817 0 -0.9997408 -0.02276551 0 -0.9976694 0.0682336 0 -0.9873267 0.1587011 0 -0.9688066 0.2478182 0 -0.9422609 0.3348798 0 -0.907918 0.4191478 0 -0.8660048 0.5000358 0 -0.8169876 0.5766552 0 -0.7611774 0.648544 0 -0.6989892 0.7151322 0 -0.631035 0.7757543 0 -0.55793 0.8298881 0 -0.480251 0.8771312 0 -0.3984029 0.9172105 0 -0.3133141 0.9496496 1 -1.30818e-5 0 1 1.30668e-5 0 1 -1.38416e-5 0 1 -1.30436e-5 0 1 1.30174e-5 0 1 -1.3817e-5 0 1 -6.54622e-6 0 1 -6.54022e-6 0 1 -5.19455e-6 0 1 -1.38318e-5 0 1 -1.38939e-5 0 1 6.54433e-6 0 1 6.91276e-6 0 1 6.9098e-6 0 1 6.91659e-6 0 1 -1.38316e-5 0 1 6.50111e-6 0 1 1.38802e-5 0 1 6.90856e-6 0 1 -6.50821e-6 0 1 1.96307e-5 0 1 -1.30943e-5 0 1 -1.30917e-5 0 1 6.95565e-6 0 1 6.53723e-6 0 1 -6.54733e-6 0 1 -6.54845e-6 0 1 -6.53339e-6 0 1 -6.94676e-6 0 1 6.94705e-6 0 1 6.9208e-6 0 1 -6.91286e-6 0 1 -5.88028e-6 0 1 1.38255e-5 0 1 -1.3002e-5 0 1 6.912e-6 0 1 6.90808e-6 0 1 -1.30314e-5 0 1 6.9325e-6 0 1 6.52188e-6 0 1 1.3082e-5 0 1 -1.62468e-6 0 1 1.3816e-5 0 1 1.30314e-5 0 1 6.91047e-6 0 1 8.68442e-6 0 1 -1.73303e-6 0 1 -3.4603e-6 0 1 -3.27268e-6 0 1 1.30948e-5 0 1 6.92003e-6 0 1 -1.30668e-5 0 1 -1.3816e-5 0 1 -2.61744e-5 0 1 -1.30562e-5 0 1 9.79215e-6 0 1 6.54407e-6 0 1 -1.38949e-5 0 1 -3.26115e-6 0 1 6.54091e-6 0 1 -6.54776e-6 0 1 6.54579e-6 0 1 -6.9402e-6 0 1 -1.38209e-5 0 1 -1.30174e-5 0 1 -6.50855e-6 0 1 1.38316e-5 0 1 -3.26379e-6 0 0 -0.04984003 0.9987573 0 -0.14906 0.9888282 0 -0.2466965 0.9690928 0 -0.3421301 0.9396527 0 -0.4338363 0.9009917 0 -0.5214501 0.8532819 0 -0.603767 0.7971609 0 -0.6801964 0.73303 0 -0.7497975 0.6616674 0 -0.8119148 0.5837761 0 -0.8660466 0.4999635 0 -0.911491 0.41132 0 -0.9479271 0.3184876 0 -0.9749255 0.2225316 0 -0.9922399 0.1243385 0 -0.9996892 0.02493023 0 -0.9972035 -0.07473492 0 -0.9848057 -0.1736603 0 -0.9626277 -0.2708282 0 -0.9308679 -0.365356 0 -0.8898828 -0.4561894 0 -0.8400456 -0.5425159 0 -0.7818157 -0.6235096 0 -0.7158369 -0.6982676 0 -0.642767 -0.7660619 0 -0.5634105 -0.8261772 0 -0.4782109 -0.8782451 0 -0.3883957 -0.9214927 0 -0.2948075 -0.9555568 0 -0.1981173 -0.9801784 0 -0.09952741 -0.9950348 0 -0.01459741 -0.9998935 0.004927456 0 -0.999988 0 0.09952741 -0.9950349 0 0.1981173 -0.9801784 0 0.2948074 -0.9555568 0 0.3883959 -0.9214926 0 0.4782111 -0.8782449 0 0.5634099 -0.8261775 0 0.6427663 -0.7660623 0 0.7158363 -0.6982682 0 0.7818152 -0.6235104 0 0.8400451 -0.5425168 0 0.8898832 -0.4561884 0 0.9308683 -0.3653549 0 0.9626277 -0.2708282 0 0.9848057 -0.1736603 0 0.9972035 -0.07473492 0 0.9996893 0.02492779 0 0.9922397 0.1243398 0 0.9749261 0.2225293 0 0.9479271 0.3184876 0 0.911491 0.41132 0 0.866046 0.4999644 0 0.8119142 0.5837768 0 0.7497981 0.6616667 0 0.6801964 0.73303 0 0.603767 0.7971609 0 0.5214498 0.853282 0 0.4338365 0.9009916 0 0.3421303 0.9396526 0 0.2466965 0.9690928 0 0.14906 0.9888283 0 0.04984003 0.9987573 0 0.1490612 0.988828 0 0.2466989 0.9690923 0 0.3421323 0.9396519 0 0.4338403 0.9009898 0 0.5214501 0.8532819 0 0.6037639 0.7971633 0 0.7497975 0.6616674 0 0.8119131 0.5837785 0 0.8660453 0.4999656 0 0.9479261 0.3184906 0 0.974925 0.2225338 0 0.99224 0.1243373 0 0.9996892 0.02493023 0 0.9972035 -0.07473421 0 0.9626284 -0.2708256 0 0.9308692 -0.3653526 0 0.8898828 -0.4561894 0 0.8400442 -0.5425181 0 0.7818176 -0.6235072 0 0.7158345 -0.6982701 0 0.6427698 -0.7660594 0 0.5634071 -0.8261795 0 0.4782071 -0.8782472 0 0.3883957 -0.9214927 0 0.2948052 -0.9555574 0 0.1981185 -0.9801782 -0.002075493 0.09450113 -0.9955226 0 -0.09952741 -0.9950349 0 -0.1981185 -0.9801782 0 -0.2948052 -0.9555574 0 -0.3883959 -0.9214926 0 -0.4782074 -0.878247 0 -0.5634065 -0.8261799 0 -0.6427692 -0.7660599 0 -0.7158339 -0.6982707 0 -0.7818171 -0.623508 0 -0.8400436 -0.542519 0 -0.8898832 -0.4561884 0 -0.9308696 -0.3653516 0 -0.9626284 -0.2708256 0 -0.9972035 -0.07473421 0 -0.9996893 0.02492779 0 -0.9922399 0.1243385 0 -0.9749255 0.2225314 0 -0.9479261 0.3184906 0 -0.8660448 0.4999665 0 -0.8119125 0.5837792 0 -0.7497981 0.6616667 0 -0.6037639 0.7971633 0 -0.5214498 0.853282 0 -0.4338406 0.9009897 0 -0.3421325 0.9396518 0 -0.2466988 0.9690923 0 -0.1490612 0.9888281 -1 -4.55573e-5 0 -1 2.27775e-5 0 -1 4.54814e-5 0 -1 -4.55311e-5 0 -1 4.5557e-5 0 -1 4.55311e-5 0 -1 2.21843e-5 0 -1 -4.44454e-5 0 -1 2.26367e-5 0 -1 -2.25963e-5 0 -1 -4.5555e-5 0 -1 -4.55561e-5 0 -1 4.5556e-5 0 -1 -2.26688e-5 0 -1 2.23344e-5 0 -1 -2.22747e-5 0 -1 4.44454e-5 0 -1 4.54205e-5 0 -1 2.22588e-5 0 -1 -2.23013e-5 0 -1 -4.54814e-5 0 -1 -4.54215e-5 0 -1 1.12841e-5 0 -1 1.12567e-5 0 -1 -2.24185e-5 0 -1 1.124e-5 0 -1 -1.12098e-5 0 -1 1.12714e-5 0 -1 -2.24901e-5 0 -1 -1.11508e-5 0 -1 -1.12355e-5 0 -1 -1.12249e-5 0 -1 1.13296e-5 0 -1 -2.24406e-5 0 -0.03721565 -0.04819566 0.9981444 -0.03736078 -0.1444537 0.988806 -0.03739571 -0.2391581 0.9702603 -0.03741335 -0.3315861 0.9426829 -0.03749006 -0.4211849 0.9061996 -0.0375511 -0.5065795 0.8613752 -0.03765118 -0.5873337 0.8084686 -0.03768801 -0.6626571 0.7479742 -0.03775537 -0.731755 0.6805213 -0.03783738 -0.7940295 0.6067006 -0.03786385 -0.8488652 0.5272518 -0.03791075 -0.8957627 0.4429132 -0.03796744 -0.9343453 0.3543409 -0.03802567 -0.9641763 0.2625226 -0.03808468 -0.9850115 0.1682326 -0.03813374 -0.9966478 0.0723806 -0.03163695 -0.9994994 2.15682e-6 -0.03818535 -0.9989789 -0.02414876 -0.03823578 -0.9919824 -0.120454 -0.03827989 -0.9757283 -0.215613 -0.03832936 -0.9503549 -0.3087984 -0.03837859 -0.9161123 -0.3990808 -0.03841096 -0.8733412 -0.4855924 -0.03848505 -0.8223501 -0.5676789 -0.03850889 -0.7637724 -0.6443361 -0.03854739 -0.6979736 -0.7150853 -0.03859221 -0.625777 -0.7790467 -0.03863906 -0.5475506 -0.8358801 -0.03866755 -0.464339 -0.8848131 -0.03870505 -0.376826 -0.9254752 -0.03873676 -0.2857962 -0.9575073 -0.03882199 -0.1918734 -0.9806516 -0.03879034 -0.0965532 -0.9945717 -0.03881537 0 -0.9992464 -0.03889238 0.09655243 -0.9945678 -0.03890836 0.191875 -0.9806478 -0.03894644 0.2857928 -0.9574998 -0.03899359 0.3768208 -0.9254651 -0.03899091 0.4643355 -0.8848009 -0.03081971 0.5168723 -0.8555076 -0.03900706 0.5475419 -0.8358687 -0.0390197 0.6257687 -0.7790322 -0.03905719 0.6979587 -0.7150722 -0.03908467 0.7637544 -0.6443227 -0.03908461 0.8223327 -0.5676631 -0.03912049 0.8733175 -0.4855782 -0.03913843 0.9160844 -0.3990711 -0.03915899 0.9503226 -0.3087936 -0.03939509 0.9756866 -0.2156012 -0.03615492 0.9642426 0.2625434 -0.03623032 0.9344055 0.3543642 -0.03633511 0.895815 0.4429394 -0.03640592 0.8489097 0.5272825 -0.03649187 0.7940685 0.606732 -0.03656852 0.7317869 0.6805519 -0.03662401 0.6626808 0.7480061 -0.03675377 0.5873531 0.8084958 -0.03680306 0.5065937 0.8613992 -0.03690159 0.4211937 0.9062198 -0.03697574 0.3315926 0.9426979 -0.03703618 0.2391603 0.9702736 -0.03709524 0.1444534 0.988816 -0.03716576 0.04819571 0.9981462 -0.03616148 0.9857089 0.1645308 -0.0348038 0.9934863 0.1085066 -0.04042446 0.9963398 0.07531958 -0.03751313 0.9984118 -0.0420348 -0.05541098 0.9981722 -0.02412581 -0.03277921 0.999426 0.008567333 -0.02938681 0.988504 -0.1483118 -0.03322869 0.9921602 -0.120475 -0.04448467 0.9931535 -0.1080157 -0.04910969 0.9856815 -0.1613078 -0.04392808 0.9964103 0.07236629 -0.03479325 0.9851295 0.1682534 -0.03265583 0.06282454 0.9974902 -0.03275424 0.1583523 0.9868393 -0.03283506 0.2522696 0.9670998 -0.03287744 0.3439411 0.9384156 -0.03297644 0.4324824 0.9010392 -0.03305143 0.5168676 0.8554272 -0.03308713 0.5966529 0.8018171 -0.0331785 0.6707464 0.7409443 -0.03326833 0.738774 0.6731317 -0.03336137 0.7999665 0.5991166 -0.03343427 0.8537466 0.5196143 -0.03349834 0.8996842 0.4352544 -0.03358644 0.9372814 0.3469516 -0.03367102 0.9662531 0.2553848 -0.03056687 0.9664841 -0.2549 -0.03067433 0.9373668 -0.3469908 -0.03069669 0.899761 -0.435302 -0.03070127 0.8538083 -0.5196815 -0.03073078 0.800035 -0.5991659 -0.03074848 0.7388511 -0.6731669 -0.03078234 0.6708222 -0.7409791 -0.03078484 0.5966958 -0.8018769 -0.03085261 0.4324696 -0.9011205 -0.03089219 0.3439189 -0.9384911 -0.03088009 0.2522997 -0.9671563 -0.0309531 0.1583819 -0.9868927 -0.03093886 0.06293064 -0.9975382 -0.03094309 -0.03300249 -0.9989762 -0.03105461 -0.1287051 -0.9911966 -0.03102183 -0.2234276 -0.9742268 -0.03107625 -0.315784 -0.9483221 -0.03112095 -0.4053 -0.9136539 -0.03115499 -0.4910297 -0.8705856 -0.0311799 -0.572418 -0.819369 -0.03125011 -0.6483818 -0.7606738 -0.0312789 -0.7183385 -0.6949903 -0.0313422 -0.7817162 -0.6228463 -0.03135311 -0.8379182 -0.5448946 -0.0314058 -0.8863082 -0.4620298 -0.03144681 -0.9265516 -0.3748509 -0.03148794 -0.958242 -0.2842198 -0.03154581 -0.9810917 -0.1909558 -0.03158795 -0.9948889 -0.09590834 -0.03168779 -0.9948861 0.09590375 -0.0317341 -0.9810866 0.1909506 -0.03178453 -0.9582371 0.2842032 -0.03183978 -0.9265482 0.3748265 -0.03191453 -0.8863015 0.4620078 -0.03198248 -0.8379051 0.5448783 -0.03201842 -0.7816936 0.6228402 -0.03206688 -0.7183117 0.6949821 -0.03212869 -0.6483458 0.7606678 -0.03219705 -0.5722461 0.8194497 -0.03226459 -0.4911258 0.870491 -0.03231412 -0.4053493 0.9135907 -0.0323913 -0.3157784 0.9482799 -0.03249007 -0.2233838 0.974189 -0.03252249 -0.1286459 0.9911572 -0.03261935 -0.03308457 0.9989202 5.31296e-5 1 -1.53603e-4 -4.89883e-4 1 1.61507e-4 6.41913e-5 1 -4.29808e-5 -1.41724e-4 1 -2.41689e-4 2.04322e-4 1 -4.52086e-5 1.60256e-4 1 2.89795e-5 -2.48388e-4 1 -1.04341e-5 -3.29969e-4 1 -4.64049e-5 1.64605e-4 1 -1.46727e-5 0.03485918 0.9662052 -0.2554067 0.0348525 0.9372549 -0.3468984 0.03486281 0.899622 -0.4352757 0.03485822 0.8536981 -0.5196004 0.03487092 0.7999058 -0.5991116 0.03486579 0.7387875 -0.6730359 0.03489339 0.6706662 -0.7409382 0.03487265 0.5966012 -0.8017799 0.03488099 0.51683 -0.8553773 0.03485077 0.5167971 -0.8553983 0.03487461 0.432382 -0.9010159 0.03486657 0.3439405 -0.9383439 0.03481531 0.2523859 -0.9670002 0.03486949 0.1582497 -0.9867833 0.03481793 0.06303268 -0.997404 0.034859 -0.0331428 -0.9988425 0.03490591 -0.1288099 -0.9910549 0.03486692 -0.2232738 -0.974132 0.03488051 -0.3157427 -0.9482036 0.03488302 -0.4052604 -0.9135357 0.03486156 -0.4909444 -0.8704932 0.03483992 -0.5722993 -0.8193044 0.0348581 -0.6482692 -0.760613 0.0348711 -0.7183179 -0.6948407 0.03485745 -0.7816064 -0.6227972 0.03484219 -0.8377922 -0.5448765 0.03486013 -0.8862329 -0.4619265 0.03485745 -0.9264435 -0.3748167 0.03485447 -0.958141 -0.2841673 0.03486067 -0.9809851 -0.190927 0.03485685 -0.9947805 -0.09590071 0.03486114 -0.9993922 0 0.03485953 -0.9993923 2.56335e-6 0.03485953 -0.9947804 0.09590071 0.03485399 -0.9809856 0.1909257 0.03485137 -0.9581417 0.2841653 0.03485757 -0.9264435 0.3748167 0.03484231 -0.8862366 0.4619209 0.03486895 -0.8377894 0.544879 0.03487545 -0.7816048 0.6227983 0.03482699 -0.7183197 0.694841 0.03485172 -0.6482722 0.7606106 0.03481727 -0.5722969 0.8193071 0.03488713 -0.4909482 0.87049 0.03489929 -0.4052609 0.9135348 0.03488761 -0.3157393 0.9482043 0.03491723 -0.2232743 0.9741301 0.03485095 -0.1288096 0.9910568 0.03480762 -0.0331428 0.9988444 0.03489333 0.06303149 0.9974014 0.03489893 0.1583973 0.9867585 0.03488796 0.2522453 0.9670342 0.03489363 0.3439394 0.9383434 0.03490459 0.4323841 0.9010138 0.03485208 0.5168264 0.8553805 0.03486716 0.5966002 0.8017809 0.03484666 0.6706671 0.7409396 0.03488361 0.738788 0.6730345 0.03486651 0.7999086 0.5991082 0.03485643 0.8537009 0.5195959 0.03484535 0.899622 0.4352771 0.03486436 0.9372553 0.3468961 0.03486377 0.9662053 0.2554057 0.0340721 0.9950688 0.09315168 0.05218279 0.9962321 0.06927162 0.03628504 0.9862109 0.1614673 0.03486454 0.9857237 0.1647223 0.03539019 0.9859098 -0.1634917 0.03381371 0.9958282 -0.08475178 0.07922232 0.9946734 -0.06594353 0.03627955 0.9862106 -0.1614704 0.03486627 0.9662128 0.2553766 0.03484714 0.9372421 0.3469335 0.03486776 0.8996426 0.4352327 0.03486955 0.8537068 0.5195852 0.03488653 0.7999181 0.5990945 0.03486031 0.7387323 0.6730968 0.0348618 0.6707105 0.7408996 0.03486931 0.5966089 0.8017743 0.03486198 0.5168455 0.8553686 0.03488421 0.4324328 0.9009911 0.03487724 0.3439363 0.938345 0.03488647 0.2522554 0.9670317 0.03486287 0.1583442 0.9867683 0.03479075 0.06281298 0.9974188 0.03485339 -0.03308117 0.9988449 0.03492534 -0.1286349 0.9910769 0.03488147 -0.2233498 0.9741141 0.03486734 -0.3157627 0.9481974 0.03486382 -0.4053014 0.9135181 0.03481751 -0.4910911 0.8704122 0.03486692 -0.5722084 0.8193669 0.03483235 -0.6482852 0.7606004 0.03487998 -0.7182412 0.6949194 0.03484642 -0.7816158 0.6227862 0.03483366 -0.8378214 0.5448322 0.03486472 -0.8862153 0.46196 0.03485774 -0.9264526 0.3747941 0.03485673 -0.9581393 0.2841726 0.03486114 -0.9809845 0.1909301 0.0348562 -0.9947815 0.09588968 0.03485774 -0.9947806 -0.0958985 0.0348562 -0.9809852 -0.1909269 0.0348559 -0.9581347 -0.2841885 0.03485745 -0.9264438 -0.374816 0.03483402 -0.8862131 -0.4619663 0.03486371 -0.837819 -0.5448338 0.03487682 -0.7816274 -0.6227699 0.03484874 -0.7182585 -0.6949031 0.03485399 -0.6482831 -0.7606014 0.0348562 -0.572354 -0.8192656 0.03485459 -0.4909707 -0.8704786 0.03486734 -0.4052594 -0.9135367 0.03485751 -0.3157301 -0.9482086 0.03490304 -0.2233953 -0.9741029 0.03483653 -0.1286959 -0.9910721 0.03477555 -0.03301805 -0.9988496 0.03489404 0.06293362 -0.9974076 0.0348525 0.158374 -0.986764 0.03488951 0.2522599 -0.9670304 0.03490519 0.343891 -0.9383606 0.03485053 0.4324008 -0.9010078 0.03487437 0.5966162 -0.8017686 0.03484582 0.6707363 -0.7408769 0.0348711 0.7387545 -0.673072 0.03485625 0.7999289 -0.5990817 0.03486478 0.8536886 -0.5196154 0.03485065 0.8996357 -0.4352484 0.03487259 0.937243 -0.3469288 0.0342561 0.9665575 -0.2541521 1 -4.86618e-5 0 1 -2.4616e-5 0 1 -4.92247e-5 0 1 2.46069e-5 0 1 2.55376e-5 -1.15154e-4 1 2.41815e-4 1.12439e-5 1 2.42866e-5 0 1 2.40628e-5 0 1 8.49666e-5 2.65534e-4 1 -2.44039e-5 0 1 -1.21024e-5 0 1 -1.20589e-5 0 1 -4.8158e-5 0 1 4.81058e-5 0 1 2.40529e-5 0 1 -2.43303e-5 0 1 -2.46099e-5 0 1 -2.44308e-5 0 1 1.21406e-5 0 1 1.21253e-5 0 1 -4.92305e-5 0 1 -1.22914e-5 0 1 2.40419e-5 0 1 2.4564e-5 0 1 -2.45146e-5 0 1 -1.22357e-5 0 1 1.21336e-5 0 1 -1.22023e-5 0 1 2.42014e-5 0 1 -4.92241e-5 0 1 2.40402e-5 0 1 1.22423e-5 0 1 -2.40917e-5 0 1 1.20925e-5 0 1 1.21501e-5 0 1 1.21856e-5 0 1 -2.43345e-5 0 1 2.42233e-5 0 1 -2.40929e-5 0 1 2.42248e-5 0 1 -1.22178e-5 0 1 2.41423e-5 0 1 2.41441e-5 0 1 -2.44906e-5 0 1 -2.40796e-5 0 1 -2.45439e-5 0 1 2.45079e-5 0 1 -2.44902e-5 0 1 -2.45164e-5 0 1 2.45634e-5 0 1 -2.43333e-5 0 1 2.411e-5 0 1 -2.44221e-5 0 1 1.18131e-5 0 0.1534877 -0.9034011 -0.4003849 0.15692 -0.8777642 -0.4526657 0.1545644 -0.9354621 -0.3178373 0.154482 -0.9621691 -0.2244239 0.1544872 -0.9792066 -0.1314851 0.154784 -0.9867585 -0.04847395 0.15635 -0.9855877 -0.06458741 0.1571867 -0.987217 0.02636116 0.1548418 -0.9867495 0.04847216 0.1568667 -0.9769294 0.1449202 0.1544177 -0.9795757 0.1287893 0.1568507 -0.9580236 0.2399766 0.1531858 -0.9643113 0.2159578 0.1559901 -0.9300165 0.3327708 0.1556127 -0.9348053 0.3192552 0.1532658 -0.9285002 0.3382261 0.1563619 -0.8928703 0.4222958 0.1562298 -0.8471975 0.507788 0.1562712 -0.7933284 0.5883957 0.1562427 -0.7318508 0.6633119 0.1562432 -0.6633093 0.7318531 0.1562124 -0.588424 0.793319 0.1562302 -0.5076788 0.8472629 0.1563277 -0.4221385 0.8929506 0.1522247 -0.3399701 0.9280346 0.1560372 -0.3327303 0.9300232 0.144339 -0.2213526 0.9644528 0.1580975 -0.2692292 0.950011 0.1470715 -0.1337137 0.9800463 0.1459311 -0.04855364 0.9881026 0.1563021 -0.06420791 0.9856202 0.1618821 0.02615165 0.9864636 0.1466203 0.04854756 0.9880008 0.1605062 0.1448334 0.976351 0.146686 0.131044 0.9804646 0.1596342 0.2398497 0.9575954 0.1493793 0.2274631 0.9622611 0.1587968 0.3325808 0.9296095 0.1512179 0.3206733 0.9350411 0.1580777 0.4221632 0.8926308 0.1524841 0.4106773 0.8989399 0.1576386 0.5076998 0.8469894 0.1532968 0.4963635 0.8544726 0.1573219 0.5883579 0.7931487 0.1521896 0.5720405 0.8059827 0.1553106 0.6636312 0.7317598 0.1552754 0.6633642 0.7320092 0.1566998 0.7318063 0.6632532 0.1533381 0.7149586 0.6821449 0.1556787 0.7341879 0.6608573 0.1564818 0.7932987 0.5883798 0.1552017 0.7857547 0.5987504 0.1560269 0.8533646 0.4974178 0.1566231 0.8471599 0.5077295 0.1543967 0.8345609 0.5288383 0.1561365 0.8998741 0.4072447 0.1555379 0.8920895 0.4242457 0.1565672 0.8777898 0.4527382 0.155559 0.8929854 0.4223489 0.1526551 0.9460656 0.2857561 0.1567211 0.9205425 0.3578267 0.156248 0.9581255 0.2399632 0.1562575 0.9770262 0.1449255 0.1562523 0.9865274 0.04846698 0.15625 0.986528 -0.0484609 0.1562476 0.9770267 -0.1449332 0.1562493 0.9581163 -0.2399986 0.154972 0.8336693 -0.5300748 0.1572988 0.852518 -0.4984681 0.158412 0.8773003 -0.453045 0.1534092 0.8949452 -0.4189735 0.1545764 0.8981777 -0.4115616 0.1559067 0.9300289 -0.3327753 0.1551137 0.9295998 -0.3343412 0.1564279 0.9434236 -0.2923738 0.1412968 0.9461205 -0.2913614 0.1608437 0.9254865 -0.3429347 0.1582396 0.9216152 -0.3543809 0.1562907 0.8928807 -0.4222999 0.1562423 0.8472102 -0.507763 0.1562551 0.7933261 -0.588403 0.156244 0.731862 -0.6632992 0.1562661 0.6632562 -0.7318963 0.1562216 0.5884586 -0.7932915 0.1562436 0.507817 -0.8471776 0.1563197 0.4222841 -0.8928833 0.1536331 0.3407986 -0.9274985 0.156037 0.332733 -0.9300222 0.1443042 0.2213323 -0.9644627 0.1582419 0.2696841 -0.949858 0.1470897 0.133732 -0.980041 0.1457706 0.04855471 -0.9881262 0.1563196 0.06452453 -0.9855967 0.1619458 -0.02576279 -0.9864634 0.1464821 -0.04854953 -0.9880213 0.1605507 -0.1448324 -0.9763438 0.146719 -0.131037 -0.9804606 0.1596311 -0.2398493 -0.9575961 0.1493906 -0.2274284 -0.9622676 0.158789 -0.3325837 -0.9296097 0.1512262 -0.320683 -0.9350364 0.1580477 -0.4221661 -0.8926347 0.1525015 -0.4106757 -0.8989377 0.1576405 -0.5077008 -0.8469884 0.1533015 -0.4963599 -0.8544738 0.1573277 -0.5883566 -0.7931485 0.1521809 -0.5720326 -0.8059899 0.1552532 -0.6614 -0.7337891 0.1555917 -0.6633273 -0.7319755 0.1567037 -0.7318059 -0.6632527 0.15332 -0.7149441 -0.6821641 0.1556792 -0.7341897 -0.6608552 0.1564933 -0.7932984 -0.588377 0.1552999 -0.7863524 -0.5979397 0.1557428 -0.8467811 -0.5086317 0.1473712 -0.8462263 -0.5120378 0.1599843 -0.8601908 -0.4842282 0.1590209 -0.8424801 -0.514723 0.1563346 -0.8293796 -0.5363665 0.1563172 -0.8793874 -0.4497141 0.1567369 -0.900663 -0.4052652 0.1605759 -0.8989567 -0.4075441 0.1576057 -0.9014272 -0.403224 0.1553332 -0.891407 -0.4257528 0.1527755 -0.891997 -0.4254422 0.155873 -0.9111008 -0.3815745 0.1540985 -0.9449199 -0.2887561 0.1571175 -0.9155465 -0.3702548 0.1513899 -0.9332264 -0.3258367 0.1583977 -0.9605709 -0.2285036 0.1598523 -0.9479711 -0.2753148 0.1623098 -0.9136125 -0.3727837 0.1556642 -0.8472909 -0.5078058 0.157326 -0.6159173 -0.771942 0.156224 0.1449336 -0.9770304 0.1596381 0.2398471 -0.9575955 0.1521395 0.3405166 -0.9278481 0.1564152 0.4221179 -0.892945 0.1563197 0.5076665 -0.8472538 0.1562393 0.588428 -0.7933107 0.1562116 0.6633149 -0.7318547 0.1562489 0.7318501 -0.6633112 0.156243 0.7933323 -0.5883979 0.1562466 0.8471986 -0.507781 0.1562424 0.8929381 -0.4221963 0.155062 0.8985088 -0.4106553 0.1541301 0.8633018 -0.4805769 0.1562462 0.9581254 -0.2399643 0.1562593 0.977026 -0.1449255 0.1562494 0.9865278 -0.04846781 0.1562537 0.9865275 0.0484609 0.1562484 0.9770265 0.1449332 0.1562503 0.9581161 0.2399986 0.1562472 0.9299769 0.3327606 0.1570912 0.6138307 0.77365 0.1562239 -0.1449335 0.9770303 0.1596552 -0.2398478 0.9575924 0.1523817 -0.3400178 0.9279913 0.1563826 -0.4222745 0.8928767 0.1563302 -0.5078078 0.8471672 0.1562508 -0.5884598 0.7932849 0.1562354 -0.6632617 0.7318979 0.1562593 -0.7318588 0.6632992 0.1562312 -0.7933285 0.5884063 0.1562534 -0.8472104 0.5077595 0.156232 -0.893 0.4220696 0.1570066 -0.9490792 0.273126 0.1562545 -0.9770257 -0.1449328 0.1568598 -0.9580231 -0.2399722 0.1568273 -0.9298913 -0.3327273 0.1568025 -0.892808 -0.4222642 0.173653 0.696353 -0.6963743 0.1736712 0.6963615 -0.6963613 0.1736091 0.6963786 -0.6963597 0.1736567 0.6963553 -0.6963711 0.1737683 0.6963515 -0.6963471 0.3826878 -0.9238777 1.81371e-5 0.3827941 -0.9238337 0 -0.2079173 0.6916782 -0.6916298 -0.2079212 0.6916772 -0.6916297 -0.2077826 0.6916745 -0.6916739 -0.2078539 0.6916405 -0.6916865 0.4996743 0.8662135 -8.55897e-5 0.4995172 0.866304 1.41006e-4 0.4994054 0.8663684 -4.63548e-5 0.4975879 0.8674136 1.80071e-5 0.499326 0.8664142 1.00065e-4 0.4995779 0.8662689 5.07564e-6 0.4985455 0.8668637 4.57259e-5 0.4995124 0.8663067 1.88889e-4 0.7072348 -0.7069788 -1.93935e-6 0.7071801 -0.7070335 3.0543e-7 0.7070943 -0.7071194 -3.13974e-6 0.7070954 -0.7071182 -3.55407e-7 0.7070593 -0.7071543 -2.06372e-6 0.7070927 -0.7071209 3.53176e-7 0.7070931 -0.7071204 -3.58432e-6 0.7071091 -0.7071045 -3.78035e-6 0.7071196 -0.7070941 -7.08954e-6 0.7071729 -0.7070407 9.44131e-6 0 1 0 -5.42764e-5 1 1.1579e-4 -5.26244e-5 1 -1.12486e-4 -2.98367e-4 1 -1.25035e-4 -3.07726e-4 1 1.29838e-4 1 4.44405e-5 0 1 -1.33618e-5 0 1 -5.2154e-5 0 0.8660478 0.4999613 0 0.8660733 0.4999172 0 0.8659861 0.5000683 0 0.866046 0.4999644 0 0.8659843 0.5000713 0 0.8611688 0.5083191 4.45747e-5 0.8624892 0.5060754 0 1 1.95506e-5 0 1 2.68622e-5 0 1 -1.47142e-5 0 1 -7.22857e-5 0 0.4246544 7.33774e-6 -0.9053556 0.4246683 2.43916e-6 -0.9053491 0.4248742 -2.41132e-5 -0.9052524 0.4246325 -5.6445e-5 -0.9053658 0.4247016 2.38352e-5 -0.9053335 0.4247004 1.48908e-5 -0.905334 0.4246895 0 -0.9053391 0.4246852 -1.1969e-4 -0.9053412 0.4252943 2.36946e-4 -0.9050551 0.4247348 -2.50585e-5 -0.9053179 -0.8702865 -0.004587233 -0.4925246 -0.8883038 0.004875957 -0.4592307 -0.8175478 -0.004752576 -0.5758413 -0.8377512 0.00466299 -0.5460324 -0.755894 -0.004551768 -0.6546782 -0.7786442 0.004746854 -0.6274478 -0.6872196 -0.004449069 -0.7264362 -0.7117866 0.004716873 -0.70238 -0.6122005 -0.00432229 -0.7906908 -0.637719 0.004587113 -0.7702556 -0.531052 -0.004270613 -0.8473286 -0.55722 0.004443228 -0.8303532 -0.4445767 -0.004172384 -0.8957312 -0.4709738 0.004288613 -0.8821368 -0.3536849 -0.003988683 -0.9353561 -0.3799966 0.004233002 -0.9249783 -0.2593657 -0.003853917 -0.9657716 -0.2853889 0.004145443 -0.9584029 -0.1628198 -0.003715693 -0.9866489 -0.1876204 0.003936946 -0.9822337 -0.06413221 -0.003615856 -0.9979349 -0.08808243 0.003804802 -0.996106 0.03487533 -0.003425598 -0.9993858 0.01230812 0.003652691 -0.9999176 0.1337157 -0.003205001 -0.9910145 0.1127163 0.003528594 -0.993621 0.2310228 -0.003065824 -0.9729436 0.2117675 0.003372907 -0.9773143 0.3261061 -0.002897322 -0.9453288 0.3087745 0.003156244 -0.95113 0.4180191 -0.00271219 -0.9084342 0.4027106 0.002956986 -0.9153226 0.5058318 -0.002495586 -0.8626285 0.4925974 0.002747654 -0.870253 0.5886896 -0.002310633 -0.8083559 0.5774161 0.002548575 -0.8164461 0.6656539 -0.002074122 -0.7462578 0.6565186 0.002279698 -0.7543065 0.7363123 -0.001856267 -0.6766393 0.7288907 0.002079606 -0.684627 0.7996641 -0.001616239 -0.6004456 0.7939066 0.001871347 -0.6080369 0.8551419 -0.00136429 -0.5183923 0.8509433 0.001642286 -0.525255 0.9021824 -0.001080393 -0.4313535 0.8993786 0.001353621 -0.4371685 0.9404421 -8.07264e-4 -0.3399531 0.9387269 0.001114308 -0.3446605 0.9694803 -5.75622e-4 -0.2451689 0.9685624 8.75879e-4 -0.2487697 0.9889736 -2.92811e-4 -0.1480926 0.988651 5.77134e-4 -0.1502291 0.9987735 0 -0.04951268 0.9987366 2.98534e-4 -0.05025154 0.9987369 2.93835e-4 0.05024558 0.9886485 5.80623e-4 0.1502465 0.9685612 8.63952e-4 0.2487739 0.9387286 0.001116454 0.3446553 0.8993858 0.00137031 0.4371538 0.8509538 0.001639127 0.5252382 0.7939125 0.001852035 0.6080293 0.7288647 0.002090036 0.6846546 0.6564891 0.002306938 0.754332 0.5774421 0.002550363 0.8164277 0.4925952 0.002749562 0.8702543 0.4027162 0.002964496 0.9153202 0.3087708 0.00315994 0.9511313 0.211803 0.003376305 0.9773066 0.1127541 0.003476262 0.9936168 0.01229876 0.0036152 0.9999179 -0.08812946 0.003824472 0.9961017 -0.187588 0.00398606 0.9822398 -0.2853521 0.004143655 0.9584138 -0.3799904 0.004177927 0.9249811 -0.4709489 0.004303812 0.88215 -0.5571637 0.004489779 0.8303905 -0.6377385 0.004586994 0.7702394 -0.7118098 0.004663944 0.7023568 -0.7786483 0.004746854 0.6274428 -0.8377539 0.004667997 0.5460281 -0.8883038 0.004878461 0.4592307 -0.9079373 -0.002216219 0.4191005 -0.9139295 -7.7935e-4 0.4058725 -0.9233752 0.02514719 0.3830742 -0.9138955 -7.90489e-4 -0.4059488 -0.9233819 0.02516603 -0.3830568 -0.8702962 -0.004575967 0.4925076 -0.8175421 -0.004734098 0.5758496 -0.7559484 -0.004505813 0.6546158 -0.6873507 -0.0044775 0.726312 -0.6121342 -0.0043509 0.790742 -0.5309005 -0.004239141 0.8474236 -0.4447097 -0.004134654 0.8956653 -0.3538392 -0.004015564 0.9352977 -0.2593641 -0.003875017 0.9657719 -0.1626174 -0.003689467 0.9866823 -0.06422692 -0.003584563 0.997929 0.0348162 -0.003466784 0.9993878 0.1334893 -0.003211379 0.9910451 0.2310471 -0.003064036 0.9729378 0.3260734 -0.00288248 0.9453401 0.4180258 -0.002703666 0.9084312 0.5058118 -0.00249195 0.8626403 0.5887537 -0.002310514 0.8083092 0.6657161 -0.002047061 0.7462023 0.7363124 -0.001847982 0.6766393 0.7996029 -0.001601755 0.6005269 0.8551504 -0.00137031 0.5183783 0.9021931 -0.001093149 0.4313311 0.9404402 -8.05699e-4 0.3399583 0.9694783 -5.68763e-4 0.245177 0.9889727 -2.88089e-4 0.1480982 0.9987736 0 0.04951268 -0.9079248 -0.002212345 -0.4191273 0.0843532 7.73719e-5 -0.996436 0.08463472 -1.04395e-5 -0.996412 0.2586364 4.85575e-5 -0.9659748 0.2588339 0 -0.9659219 0.4246711 0 0.9053477 0.4246623 -4.6704e-5 0.9053519 0.4246782 9.02276e-6 0.9053444 0.4234662 9.42796e-4 0.9059115 0.4252049 1.88698e-4 0.9050971 0.4246916 0 0.9053381 0.4247127 7.78375e-5 0.9053282 0.1908354 -0.6940986 0.6941246 0.1910691 -0.6940785 0.6940805 0.190886 -0.6941072 0.6941022 0.1910244 -0.6932594 0.694911 0.1907657 -0.6941152 0.6941272 0.190894 -0.6940857 0.6941214 0.1906505 -0.694214 0.6940601 0.1908341 -0.6940883 0.6941353 0.1912414 -0.6939985 0.694113 3.30998e-4 -0.9999995 0.001041173 -3.1893e-5 -1 2.72658e-5 1.1197e-4 -1 -1.15315e-4 2.27241e-5 -1 -3.0672e-4 -6.98076e-5 -1 -3.67229e-5 0 -1 0 1.19023e-5 -1 1.42908e-5 0.001464068 -0.9999988 -6.66615e-4 4.2443e-5 -1 0 2.39813e-5 -1 2.57477e-6 3.9744e-6 -1 1.44811e-5 0.1582174 -0.941979 0.2960455 0.1547303 -0.9543291 0.2555674 0.1478178 -0.9598999 0.2382066 0.1520172 -0.9279881 0.3401895 0.2581374 -2.22098e-4 0.9661083 0.2572368 0 0.9663485 0.08456867 8.46049e-5 0.9964178 0.08471053 0 0.9964056 -0.7280736 -0.4537073 0.5138664 -0.6737027 -0.4537296 0.5833131 -0.6119008 -0.4529984 0.6483594 -0.5582717 -0.4539459 0.6944536 -0.5457822 -0.4529693 0.7049403 -0.5006835 -0.4542732 0.7368527 -0.4731833 -0.4529426 0.7556061 -0.3974786 -0.4537144 0.7975927 -0.3144929 -0.4530137 0.83419 -0.2478616 -0.4540141 0.8558247 -0.2312352 -0.4529992 0.8610006 -0.1795141 -0.4542329 0.8726095 -0.1447824 -0.4529796 0.879686 -0.05835044 -0.4538108 0.8891857 0.03179663 -0.453031 0.8909277 0.09346586 -0.4540957 0.8860368 0.1189907 -0.4529777 0.8835453 0.1956867 -0.4537125 0.8693974 0.2059544 -0.4530732 0.8673567 0.2725979 -0.4542739 0.8481307 0.2906323 -0.4530891 0.8427592 0.356718 -0.454157 0.8163907 0.3726087 -0.4531143 0.8098458 0.4321892 -0.4543509 0.7789595 0.4508572 -0.4530498 0.7690733 0.5094447 -0.454215 0.7308591 0.5248573 -0.4530701 0.7205917 0.5719308 -0.4543163 0.6830021 0.5935198 -0.4530078 0.6652204 0.6558824 -0.4535089 0.6034469 0.7130429 -0.4529969 0.5351296 0.7548058 -0.4539485 0.4734967 0.7623119 -0.4530949 0.4621533 0.7905326 -0.4543133 0.4106795 0.8043 -0.4530346 0.3845273 0.8399926 -0.4541381 0.2969365 0.8380177 -0.4536436 0.3032062 0.8643178 -0.453011 0.218485 0.878879 -0.4539993 0.1464805 0.8816223 -0.4531006 0.1320682 0.8876198 -0.4543532 0.07546079 0.8903933 -0.4530413 0.04419499 0.8900389 -0.453739 -0.04418146 0.8816155 -0.453114 -0.1320681 0.8642684 -0.45304 -0.218621 0.8670613 -0.4539268 -0.2053179 0.8384335 -0.4530687 -0.3029161 0.846228 -0.4540404 -0.2788292 0.8027734 -0.4537687 -0.3868449 0.8037093 -0.453995 -0.3846297 0.7623344 -0.4530848 -0.462126 0.7128363 -0.4530466 -0.5353628 0.6566415 -0.4531021 -0.6029267 0.5924643 -0.4539026 -0.6655512 0.5927156 -0.4539228 -0.6653137 0.5248503 -0.4530919 -0.7205831 0.450898 -0.4530411 -0.7690546 0.3725908 -0.4531076 -0.8098578 0.2906199 -0.4530066 -0.8428079 0.3081774 -0.4539403 -0.8360413 0.2059382 -0.4530796 -0.8673571 0.1190391 -0.4529826 -0.8835363 0.1419958 -0.4539586 -0.8796356 0.03102606 -0.4530921 -0.8909236 -0.05631726 -0.4530102 -0.8897247 -0.03712862 -0.4539122 -0.8902725 -0.1445799 -0.4535935 -0.8794031 -0.1461663 -0.4534587 -0.8792104 -0.2310923 -0.4529419 -0.8610692 -0.2126337 -0.4537422 -0.865393 -0.3153702 -0.4529754 -0.8338794 -0.3041383 -0.4537559 -0.837619 -0.3954219 -0.4530065 -0.7990161 -0.3750479 -0.4540212 -0.8082104 -0.478594 -0.4535391 -0.7518312 -0.4744058 -0.4539733 -0.7542197 -0.5456506 -0.4529618 -0.7050469 -0.6127986 -0.4529191 -0.6475664 -0.6031367 -0.4538004 -0.6559661 -0.6730618 -0.4529787 -0.584635 -0.6571347 -0.4539851 -0.6017239 -0.7271064 -0.4538397 -0.5151173 -0.7280967 -0.4536886 -0.5138501 -0.8103035 -0.4529561 0.3718053 -0.8082314 -0.4542445 0.3747319 -0.7763586 -0.4528178 0.4384329 -0.7618691 -0.4541338 0.4618636 -0.7617268 -0.4541755 -0.4620574 -0.7763723 -0.4528036 -0.4384235 -0.7973856 -0.4546834 -0.3967859 -0.8102602 -0.4530074 -0.371837 -0.8082669 -0.4542019 -0.374707 -0.7973507 -0.4546974 0.3968403 -0.6880233 -0.4541077 -0.5660478 -0.5573344 -0.4539242 -0.6952203 -0.416292 -0.4540017 -0.7877712 -0.2546101 -0.4540504 -0.8538219 -0.08282363 -0.4541683 -0.8870578 0.02277201 -0.4536238 -0.8909023 0.08973985 -0.4542667 -0.8863344 0.1957799 -0.45374 -0.869362 0.2599459 -0.4541806 -0.8521434 0.3636212 -0.4537159 -0.8135856 0.4321002 -0.4543758 -0.7789944 0.5105377 -0.4542118 -0.730098 0.6485837 -0.4537817 -0.6110823 0.6974798 -0.4544696 -0.5540571 0.7516801 -0.4543444 -0.4780672 0.8316074 -0.4539374 -0.3199532 0.8789457 -0.4539635 -0.1461908 0.8893061 -0.4543512 -0.05195909 0.8906556 -0.4540575 0.02375698 0.8672689 -0.4539366 0.2044172 0.8125833 -0.4539378 0.3655803 0.7217285 -0.4539086 0.5225659 0.6613795 -0.454187 0.5969015 0.6096854 -0.4539903 0.6497512 0.1419252 -0.4539999 0.8796258 0.04245072 -0.4537403 0.8901223 -0.05614203 -0.4540061 0.8892281 -0.1292019 -0.4537893 0.8816929 -0.3033338 -0.4537767 0.8378993 -0.3934828 -0.4540442 0.7993842 -0.4582644 -0.4537322 0.7642779 -0.6025589 -0.4537739 0.6565151 -0.6703857 -0.4541229 0.5868181 -0.7272084 -0.4538092 0.5150002 -0.2626981 -1.49509e-4 -0.9648781 -0.2662874 2.95057e-4 -0.9638937 -0.002169191 -0.9999281 -0.0117948 -0.2663331 2.736e-4 0.9638811 -0.2630366 -1.66328e-4 0.9647859 -2.69602e-5 -0.7070571 0.7071565 -7.08015e-6 -0.7071015 0.707112 1.87087e-5 -0.7070577 0.7071559 -0.001108288 -0.7071868 0.707026 3.98568e-5 -0.7070784 0.7071352 -8.25982e-4 -0.706312 0.7079002 0.004204154 -0.710201 0.7039864 -0.2580699 -0.6838905 0.6824176 -0.3343829 0 0.9424374 -0.3350844 1.64661e-4 0.9421882 -0.3340732 8.2524e-5 0.9425472 -0.3296785 -0.002695977 0.9440894 -0.7351195 -0.174468 0.6551033 -0.6169762 -0.1739881 0.7675081 -0.64144 -0.1793577 0.7459126 -0.5391917 -0.1792656 0.8228828 -0.5060347 -0.1744728 0.8446823 -0.4280799 -0.1741915 0.8867948 -0.2739291 -0.1736367 0.9459457 -0.3086982 -0.1793432 0.9340993 -0.1847498 -0.1792452 0.9663016 -0.1423123 -0.1741716 0.9743775 -0.05780827 -0.1746034 0.9829405 0.0705077 -0.1793298 0.9812592 0.1033492 -0.1745327 0.9792126 0.1975017 -0.1793487 0.9637568 0.2161045 -0.1755324 0.9604621 0.321228 -0.1791643 0.9298993 0.4778087 -0.1723612 0.8613888 0.4391428 -0.1798793 0.8802256 0.549943 -0.1789225 0.8158121 0.5631167 -0.1750972 0.8076141 0.6511639 -0.1794115 0.7374261 0.6736471 -0.1753945 0.717939 0.7424528 -0.1730713 0.6471555 0.8340733 -0.1746732 0.5232697 0.8193784 -0.1793556 0.5444728 0.8831467 -0.1793412 0.4334614 0.8978689 -0.1750622 0.4039613 0.933004 -0.1734476 0.3153089 0.9650365 -0.1793954 0.191107 0.971309 -0.1742042 0.1619006 0.9817091 -0.1792914 0.06404644 0.984305 -0.174529 0.02614051 0.9826707 -0.1739173 -0.0641179 0.9582497 -0.173955 -0.2269301 0.9650391 -0.1793809 -0.1911075 0.9320111 -0.1792494 -0.3149999 0.9189506 -0.1743175 -0.3537557 0.8839833 -0.1742342 -0.4338386 0.8194124 -0.1790096 -0.5445356 0.7415505 -0.1798186 -0.6463499 0.71662 -0.1740021 -0.6754103 0.6517556 -0.1746075 -0.7380562 0.5499738 -0.1789091 -0.8157944 0.4018243 -0.1736816 -0.8990951 0.4390948 -0.1798768 -0.88025 0.3212717 -0.1794709 -0.9298252 0.2870381 -0.1743956 -0.9419105 0.1569114 -0.174334 -0.9721042 0.1975018 -0.1793469 -0.9637572 0.02520889 -0.1735678 -0.9844993 0.07044297 -0.1798278 -0.9811728 -0.05781131 -0.1794271 -0.9820712 -0.09146487 -0.1748636 -0.9803352 -0.1849479 -0.173287 -0.96735 -0.3360863 -0.1745859 -0.9255084 -0.308753 -0.17934 -0.9340819 -0.4277018 -0.179337 -0.8859512 -0.4599403 -0.1746806 -0.8705986 -0.5397543 -0.1736075 -0.8237268 -0.6665648 -0.1742089 -0.7248052 -0.6414043 -0.1793646 -0.7459416 -0.734368 -0.1796982 -0.6545321 -0.760649 -0.1740692 -0.6253902 -0.8038133 -0.1727489 0.5692468 -0.8037366 -0.1727092 -0.5693673 -0.7258486 -0.1770898 -0.6646676 -0.6158995 -0.1737186 -0.7684332 -0.5285397 -0.1779078 -0.8300571 -0.4143627 -0.1764686 -0.8928396 -0.2813418 -0.1748617 -0.9435413 -0.1840602 -0.1735767 -0.9674673 -0.04087382 -0.176308 -0.9834861 0.09908181 -0.1745351 -0.9796532 0.2162441 -0.1755259 -0.9604318 0.3405076 -0.1758176 -0.9236572 0.4777893 -0.1723511 -0.8614016 0.5643642 -0.1747078 -0.8068274 0.6545504 -0.1758758 -0.7352766 0.7712917 -0.1721365 -0.6127629 0.8309816 -0.1741786 -0.5283289 0.886704 -0.1765378 -0.4273061 0.9346925 -0.1776925 -0.3078559 0.9713773 -0.1741535 -0.1615447 0.9826992 -0.1760814 -0.05742597 0.9809291 -0.1755437 0.08344203 0.9584361 -0.1741061 0.226025 0.9277942 -0.1780646 0.3278582 0.8736734 -0.1750564 0.4539272 0.7975597 -0.173828 0.5776525 0.730509 -0.178893 0.6590554 0.632163 -0.1746544 0.7548946 0.3945031 -0.1724357 0.9025704 0.3012814 -0.1740874 0.9375091 0.157027 -0.1743609 0.9720807 0.04671776 -0.1751427 0.983434 -0.06210809 -0.1759536 0.9824373 -0.1984674 -0.1764531 0.9640929 -0.3352953 -0.1747301 0.9257681 -0.4346612 -0.1766095 0.8831076 -0.5533614 -0.1759591 0.8141435 -0.665915 -0.1743591 0.7253662 -0.7404966 -0.1773753 0.6482304 -0.3403735 -9.07633e-4 -0.9402899 -0.3286687 -0.002359032 -0.9444424 -0.3345004 3.10874e-5 -0.9423956 -4.07464e-5 -1 4.19182e-5 -1.18794e-5 -1 0 2.04812e-6 -1 9.53034e-6 2.93377e-5 -1 2.71503e-5 -0.06689292 0.004479765 0.9977501 -0.1991821 0.004451811 0.9799524 -0.3281282 0.004483163 0.9446226 -0.4509242 0.00445801 0.8925513 -0.565892 0.004435777 0.8244675 -0.6709055 0.004426598 0.7415297 -0.7228763 0.004930555 -0.6909599 -0.6196702 0.004449963 -0.7848498 -0.5096535 0.004449725 -0.8603683 -0.3903389 0.00446093 -0.9206604 -0.2962256 -0.00442785 -0.9551078 -0.2642471 0.004415571 -0.9644449 -0.1332013 0.004455149 -0.991079 0 0.004460096 -0.9999901 0.1331978 0.00439924 -0.9910798 0.2642537 0.004446804 -0.964443 0.3903389 0.00446397 -0.9206604 0.5096901 0.004459679 -0.8603465 0.6196831 0.004435777 -0.7848396 0.7188453 0.00444144 -0.6951559 0.8050424 0.004429578 -0.5932008 0.8769659 0.004465639 -0.4805319 0.9331319 0.004446685 -0.3595067 0.9727608 0.004457294 -0.2317687 0.9949671 0.004442095 -0.1001043 0.9999901 -0.004466831 -1.32457e-5 0.9994317 0.004462003 0.03341329 0.9860629 0.004445374 0.1663135 0.9551093 0.004441082 0.2962206 0.9070702 0.00444585 0.4209562 0.8429335 0.004430651 0.5379998 0.7635961 0.004450082 0.6456789 0.670847 0.004424989 0.7415826 0.5658796 0.00444585 0.824476 0.4508828 0.004485785 0.8925719 0.3281282 0.004469931 0.9446227 0.199177 0.004437446 0.9799535 0.06689292 0.004464507 0.9977502 -0.7986446 0.001055002 0.6018021 -0.748136 0 0.6635454 -0.7424749 -0.00454694 0.6698585 -0.8362063 -0.01631629 0.5481724 -0.8246439 0.01726073 0.5653889 -0.8922191 -0.0327748 0.4504118 -0.884817 -0.01083278 0.4658131 -0.9129897 0.001165568 0.407981 -0.9413785 -0.09866064 0.3226029 -0.9357503 -0.01129126 0.3524826 -0.9426824 -0.06074333 0.3281161 -0.9795666 0.1147046 0.1652035 -0.9911548 -0.1149409 0.06633836 -0.9928307 0.1148286 0.03319346 -0.9884 0.114787 -0.09944522 -0.9746921 0.03357076 -0.2210167 -0.9730761 -0.116905 -0.1986359 -0.9237695 0.00907278 -0.3828415 -0.9410333 -0.0691573 -0.3311702 -0.9408593 -0.07051116 -0.331379 -0.8649589 0.004109442 -0.5018259 -0.8918051 -0.02193516 -0.4518878 -0.8940846 -0.03187108 -0.4467629 -0.7300035 -0.00292468 -0.6834371 -0.7898048 -0.01312494 -0.613218 -0.8255115 -0.01019209 -0.5642933 -0.7413266 0.02733105 -0.6705877 -0.8289631 -0.01626878 -0.5590667 -0.9911916 -0.1146233 -0.06633728 -0.9734553 -0.1150533 0.197858 -0.9661525 0.0217145 0.2570564 -0.7446951 -0.006324827 0.6673748 0.1001684 -0.004427194 0.9949607 0.2316355 -0.004429876 0.9727926 0.3594438 -0.004404842 0.9331564 0.4806506 -0.00444287 0.876901 0.5932182 -0.004466891 0.8050293 0.6951707 -0.004427134 0.7188311 0.7847657 -0.004462361 0.6197766 0.8603304 -0.004439055 0.5097175 0.9206302 -0.004456758 0.3904105 0.9644575 -0.004446506 0.2642008 0.9910697 -0.004436314 0.1332717 0.9910732 -0.004433155 -0.1332455 0.9644611 -0.004452824 -0.2641873 0.9206429 -0.004425525 -0.3903807 0.8603574 -0.004454195 -0.5096717 0.7848009 -0.004441678 -0.6197322 0.6951687 -0.004454374 -0.7188328 0.5932287 -0.004417002 -0.805022 0.4805386 -0.004445552 -0.8769624 0.3593208 -0.004434645 -0.9332036 0.2317488 -0.0044927 -0.9727653 0.1001879 -0.004448294 -0.9949586 -0.03344905 -0.004434525 -0.9994306 -0.1664291 -0.004460275 -0.9860433 -0.4209083 -0.004427254 -0.9070924 -0.5380622 -0.004419982 -0.8428936 -0.6457263 -0.004469215 -0.763556 -0.7415632 -0.003845512 -0.670872 -0.645631 -0.004478752 0.7636365 -0.5380108 -0.004438579 0.8429263 -0.4209247 -0.004400551 0.907085 -0.2961671 -0.004429936 0.9551259 -0.1663491 -0.004418194 0.9860571 -0.03337687 -0.004434347 0.9994331 0 -1 -2.18101e-6 0 -1 2.99865e-6 0 -1 -3.64604e-6 0 -1 7.23246e-6 0 -1 2.99703e-6 0 -1 -2.21396e-6 0 -1 -6.99398e-7 0 -1 3.12143e-7 -5.95558e-6 -1 2.19257e-5 3.4824e-6 -1 -1.33283e-5 0 -1 1.66785e-6 0 -1 -2.18059e-6 0 -1 3.98013e-7 -1.49379e-6 -1 8.14582e-6 0 -1 2.82851e-7 0 -1 -2.59829e-7 -1.08752e-5 -1 1.5545e-5 6.25702e-6 -1 -1.5594e-5 5.69305e-6 -1 -1.53274e-5 0 -1 -1.23961e-6 0 -1 -9.06728e-7 0 -1 -2.06551e-7 -8.90806e-6 -1 1.14207e-5 0 -1 1.72293e-6 7.25652e-7 -1 3.49556e-7 0 -1 -5.47516e-7 0 -1 4.61462e-7 0 -1 1.06683e-6 7.99872e-7 -1 2.49692e-6 8.49289e-7 -1 0 8.80141e-7 -1 0 2.36615e-6 -1 -1.39413e-5 0 -1 1.93711e-7 0 -1 -5.89974e-7 -0.05070441 0 -0.9987137 -0.1513248 0 -0.9884841 -0.2505257 0 -0.9681099 -0.3473597 0 -0.9377321 -0.4404478 0 -0.8977783 -0.528902 0 -0.848683 -0.612103 0 -0.790778 -0.6890277 0 -0.724735 -0.7587037 0 -0.6514361 -0.8208081 0 -0.5712041 -0.8743446 0 -0.4853057 -0.8743347 0 0.4853235 -0.8208081 0 0.5712041 -0.7586859 0 0.6514567 -0.6890277 0 0.724735 -0.6120769 0 0.7907983 -0.5289321 0 0.8486642 -0.4404478 0 0.8977783 -0.3473597 0 0.9377321 -0.2506041 0 0.9680897 -0.1514065 0 0.9884716 -0.05070441 0 0.9987137 0.05074608 0 0.9987117 0.1513248 0 0.9884841 0.2505257 0 0.9681099 0.3473597 0 0.9377321 0.4404478 0 0.8977783 0.528902 0 0.848683 0.612103 0 0.790778 0.6890277 0 0.724735 0.7587037 0 0.6514361 0.8207989 0 0.5712172 0.8743529 0 0.4852908 0.9189581 0 0.3943554 0.9541335 0 0.2993816 0.9795313 0 0.2012919 0.9948686 0 0.1011752 0.9948691 0 -0.101171 0.9795313 0 -0.2012919 0.9541372 0 -0.2993697 0.9189581 0 -0.3943554 0.874343 0 -0.4853085 0.8207989 0 -0.5712172 0.7586859 0 -0.6514567 0.6890277 0 -0.724735 0.6120769 0 -0.7907983 0.5289321 0 -0.8486642 0.4404478 0 -0.8977783 0.3473597 0 -0.9377321 0.2506041 0 -0.9680897 0.1514065 0 -0.9884716 0.05074608 0 -0.9987117 -0.9180128 0 -0.3965507 -0.9572841 0.003950297 -0.2891222 -0.9393739 -2.21122e-4 -0.3428945 -0.9795108 0.005731463 -0.2013101 -0.99485 0.006267547 -0.1011645 -0.9999796 0.006400406 0 -0.9948485 0.006338059 0.1011757 -0.9795095 0.006114304 0.2013056 -0.9396637 -2.4777e-4 0.3420997 -0.9541344 0 0.2993788 -0.9565299 0.003756403 0.2916103 -0.9189566 9.49103e-4 0.3943578 -0.9180166 0 0.3965421 -0.9760012 0 0.2177652 -0.992016 -0.00310415 0.1260742 -0.9996755 -0.003184676 0.02527242 -0.997118 -0.003190696 -0.07579982 -0.9839274 -0.00339967 -0.1785365 -0.9541352 -0.001862347 -0.2993706 -0.9189694 9.5099e-4 -0.3943279 0.05070441 0 -0.9987137 0.1513248 0 -0.9884841 0.2505257 0 -0.9681099 0.528902 0 -0.848683 0.612103 0 -0.790778 0.7587037 0 -0.6514361 0.8743529 0 -0.4852908 0.9541335 0 -0.2993816 0.9948686 0 -0.1011752 0.9948691 0 0.101171 0.9541372 0 0.2993697 0.874343 0 0.4853085 0.7586859 0 0.6514567 0.6120769 0 0.7907983 0.5289321 0 0.8486642 0.2506041 0 0.9680897 0.1514065 0 0.9884716 0.05070441 0 0.9987137 -0.05074608 0 0.9987117 -0.1513248 0 0.9884841 -0.2505257 0 0.9681099 -0.528902 0 0.848683 -0.612103 0 0.790778 -0.7587037 0 0.6514361 -0.8743446 0 0.4853057 -0.8743347 0 -0.4853235 -0.7586859 0 -0.6514567 -0.6120769 0 -0.7907983 -0.5289321 0 -0.8486642 -0.2506041 0 -0.9680897 -0.1514065 0 -0.9884716 -0.05074608 0 -0.9987117 -0.08246356 0.006474733 -0.9965731 -0.05515068 -0.006473124 -0.9984571 -0.1917225 0.006587684 -0.9814271 -0.1644605 -0.006542563 -0.986362 -0.2985057 0.006571173 -0.9543853 -0.2721209 -0.006434857 -0.9622417 -0.401595 0.006471455 -0.9157945 -0.3763974 -0.006463229 -0.9264358 -0.4999805 0.00655806 -0.8660119 -0.4758745 -0.006549835 -0.8794888 -0.592154 0.006512522 -0.8057986 -0.5697979 -0.006492316 -0.8217594 -0.6772753 0.006489098 -0.7357012 -0.6568071 -0.006529808 -0.7540304 -0.7541188 0.006540536 -0.6567055 -0.7356716 -0.006540477 -0.6773068 -0.8217675 0.006540477 -0.5697856 -0.8057695 -0.006482362 -0.592194 -0.8794483 0.006540775 -0.4759495 -0.8660148 -0.006482481 -0.4999764 -0.926474 0.006520926 -0.3763024 -0.9157531 -0.006501972 -0.401689 -0.9622512 0.006502985 -0.2720856 -0.9543953 -0.006539285 -0.2984744 -0.9863413 0.006538629 -0.1645846 -0.9814247 -0.006502509 -0.1917377 -0.9965626 -0.006501674 -0.08258873 -0.9984605 0.006523251 0.05508303 -0.9995988 -0.006501793 0.02756941 -0.9904995 -0.00648272 0.1373635 -0.9622539 0.006521344 0.2720754 -0.9693874 -0.006501078 0.2454503 -0.9264716 0.006500959 0.3763086 -0.9364742 -0.00652188 0.3506758 -0.8794394 0.006521582 0.4759662 -0.8922445 -0.006539762 0.4515052 -0.8217977 0.006521582 0.5697421 -0.8371437 -0.006501913 0.5469445 -0.7540867 0.006527423 0.6567425 -0.7719082 -0.006520807 0.6357006 -0.6772518 0.00656718 0.735722 -0.6973288 -0.006530046 0.7167217 -0.592176 0.006561398 0.805782 -0.6141726 -0.006492435 0.789145 -0.4999931 0.006520926 0.8660048 -0.5236101 -0.006463825 0.8519337 -0.4016712 0.006476998 0.9157612 -0.4266862 -0.006530702 0.9043762 -0.2985799 0.006553411 0.9543622 -0.3247424 -0.006520807 0.94578 -0.1917335 0.006563901 0.9814251 -0.2187637 -0.006468236 0.9757564 -0.08247762 0.006569087 0.9965713 -0.1099569 -0.006485044 0.9939153 0.02748888 0.006559491 0.9996007 -0.02752763 -0.002112925 0.9996188 0.1373488 0.006543338 0.9905012 0.1099947 -0.006492197 0.993911 0.2455348 0.006515264 0.969366 0.2186908 -0.006516158 0.9757725 0.3506518 0.00647068 0.9364836 0.3247701 -0.00651586 0.9457706 0.45147 0.006520032 0.8922625 0.4266632 -0.006521344 0.9043871 0.5469204 0.006565093 0.837159 0.5236377 -0.006482839 0.8519165 0.6357085 0.006559014 0.7719014 0.6141624 -0.006463646 0.7891533 0.7167631 0.006501734 0.6972865 0.6973397 -0.006501436 0.7167114 0.7891761 0.006502509 0.6141328 0.7719236 -0.006539762 0.6356818 0.851891 0.00654006 0.5236783 0.8371339 -0.006501853 0.5469596 0.9043302 0.006520926 0.426784 0.8922526 -0.006501317 0.4514899 0.9458069 0.006559073 0.3246634 0.9364742 -0.00652188 0.3506758 0.9757714 0.006502807 0.2186965 0.9693903 -0.006482183 0.2454393 0.9939107 0.006501138 0.1099972 0.9904986 -0.006521165 0.1373687 0.9995988 -0.006501793 0.02756941 0.9939107 0.006501138 -0.1099972 0.996563 -0.00652033 -0.08258241 0.9757718 0.006503105 -0.2186944 0.9814232 -0.00652188 -0.1917449 0.945809 0.006521344 -0.324658 0.9544015 -0.006520211 -0.2984548 0.9043441 0.006538808 -0.4267541 0.9157389 -0.006521284 -0.4017211 0.8518836 0.006540834 -0.5236905 0.8660051 -0.006501793 -0.4999929 0.789149 0.006519794 -0.6141673 0.8057695 -0.006482362 -0.592194 0.7167515 0.006490707 -0.6972985 0.7356716 -0.006540477 -0.6773068 0.6356841 0.006549954 -0.7719216 0.656796 -0.006539642 -0.7540401 0.5468905 0.006552934 -0.8371785 0.569762 -0.006482779 -0.8217843 0.4515175 0.006502687 -0.8922387 0.4759043 -0.006473243 -0.8794733 0.3507292 0.006553888 -0.936454 0.3764377 -0.006491899 -0.9264193 0.2455121 0.006544113 -0.9693714 0.2721506 -0.006482481 -0.962233 0.1372607 0.006483078 -0.9905138 0.1644606 -0.006511449 -0.9863622 0.02750486 0.006558179 -0.9996002 0.05515068 -0.006532847 -0.9984567 0.9999787 0.006521165 0 0.02745068 0.006559789 0.9996017 -0.9863436 0.006509423 0.1645722 -0.9984596 0.006530761 -0.05509835 0 1 2.38863e-6 0 1 -1.08137e-6 0 1 2.4775e-6 0 1 -2.68667e-6 0 1 1.6929e-6 0 1 -1.67771e-6 0.3246693 7.70979e-4 0.9458273 0.3241615 0 0.9460018 0.3241685 -5.50599e-6 0.9459995 0.3355473 0.0112307 0.9419565 0.3405875 -0.007202088 0.9401853 0.3241813 0 0.945995 0.3240486 -0.001594364 0.9460391 0.5183797 -2.65618e-5 0.8551506 0.5180531 -5.54173e-5 0.8553485 0.5180441 -7.41588e-6 0.855354 0.5183681 5.85264e-5 0.8551576 0.5175397 3.10671e-4 0.8556591 0.5184155 -0.001717209 0.8551272 0.5180338 -5.72767e-6 0.8553602 0.51814 1.92868e-4 0.8552959 0.5179355 3.49686e-4 0.8554198 0.5180133 0 0.8553726 0.5179374 -6.28768e-5 0.8554186 0.5180246 1.07944e-4 0.8553658 0.5182504 6.42831e-5 0.8552291 0.5179645 1.39052e-4 0.8554022 0.5178672 -3.4965e-5 0.8554612 0.5181998 -1.04476e-4 0.8552597 0.5182884 -4.23093e-5 0.855206 0.5181391 -1.49234e-4 0.8552964 0.5182853 -1.26552e-4 0.8552078 0.5177957 -9.53602e-5 0.8555043 0.5179548 7.66319e-5 0.855408 0.5183167 -2.9292e-4 0.8551889 0.5180014 4.3095e-4 0.8553797 0.5182276 -2.72407e-5 0.8552428 0.51802 0 0.8553684 0.5180807 -8.61505e-5 0.8553318 0.5181829 1.53596e-4 0.8552699 0.5181536 -5.01949e-4 0.8552874 0.5228537 -7.70501e-4 0.8524221 0.5226577 0.001149594 0.852542 0.5179685 6.7659e-5 0.8553998 0.5180469 -2.42211e-5 0.8553523 0.5180492 4.25887e-5 0.8553509 0.517833 -7.34009e-5 0.8554818 0.5180045 3.86823e-5 0.855378 0.5182269 -6.1609e-5 0.8552433 0.5181863 2.01734e-4 0.8552677 0.5180636 -2.91768e-5 0.8553422 0.5180501 -2.59737e-5 0.8553503 0.5180858 3.95123e-5 0.8553286 0.517998 -3.58238e-5 0.8553819 0.8325187 0.5199744 0.1911524 0.7263092 0.6690262 0.1577306 0.6748961 0.6769647 0.2936566 0.5955638 0.70336 0.3880575 0.5145946 0.7073757 0.4845741 0.4421446 0.6809111 0.5838393 0.4702584 0.6988485 0.5389507 0.3582361 0.6484792 0.6716709 0.2867902 0.588397 0.7560028 0.2238831 0.5089543 0.831169 0.1708124 0.4136751 0.8942573 0.1706928 0.4134738 0.8943733 0.1295613 0.3049866 0.9435026 0.1014431 0.186847 0.9771375 0.1013289 0.1873993 0.9770435 0.08678376 0.06308507 0.9942278 0.08714431 -0.06219607 0.9942523 0.0881468 -0.06300675 0.9941129 0.09731155 -0.1819685 0.9784774 0.1014586 -0.1868467 0.9771359 0.1294458 -0.3049326 0.9435359 0.1295182 -0.3049702 0.9435138 0.1709526 -0.4140482 0.8940578 0.1703249 -0.4138814 0.8942549 0.2259997 -0.5094808 0.8302732 0.2234179 -0.5091491 0.831175 0.288699 -0.5882378 0.7554001 0.286917 -0.5882996 0.7560305 0.3573955 -0.6488031 0.6718059 0.3579514 -0.6486983 0.671611 0.4259912 -0.6854084 0.5905479 0.4422019 -0.6808948 0.5838149 0.5155197 -0.7070164 0.4841151 0.514613 -0.7073665 0.4845679 0.595619 -0.7033156 0.3880531 0.6747844 -0.6770818 0.2936433 0.7560477 -0.6244681 0.1960391 0.8324933 -0.520011 0.1911634 0.7261818 -0.6691698 0.1577081 0.6748961 -0.6769648 0.2936563 0.595551 -0.7033683 0.3880621 0.4704887 -0.6987911 0.5388241 0.1295886 -0.3048898 0.9435302 0.1013289 -0.1873993 0.9770435 0.0872305 0.0634067 0.9941683 0.1032944 0.188947 0.9765394 0.1294174 0.3049548 0.9435326 0.1704329 0.4134744 0.8944225 0.2237448 0.5089722 0.8311952 0.2865859 0.5884336 0.756052 0.3580632 0.6484693 0.6717726 0.4242309 0.6858729 0.5912754 0.5155722 0.7069903 0.4840973 0.5956292 0.7033089 0.3880495 0.6747843 0.6770817 0.2936437 0.756006 0.6245183 0.1960406 0.23535 0.653949 0.7190002 0.2513997 0.6693325 0.6991369 0.2149223 0.6371487 0.7401689 0.1880536 0.6372744 0.7473402 0.1713632 0.6104341 0.7733078 0.1540123 0.60913 0.7779724 0.1288511 0.5680531 0.8128426 0.09286987 0.5268273 0.8448836 0.0988996 0.5573328 0.8243781 0.06301546 0.4881933 0.8704576 0.04417192 0.4777964 0.8773595 0.04081088 0.449968 0.8921117 0.01588052 0.4079773 0.9128541 0.01186859 0.4055529 0.9139945 -0.01090824 0.3548145 0.9348731 -0.01719093 0.3504366 0.9364287 -0.02477639 0.3051735 0.9519744 -0.04502338 0.2750108 0.9603863 -0.05047309 0.2136204 0.975612 -0.06177145 0.1617071 0.9849037 -0.07005941 0.18485 0.9802664 -0.06931358 0.1086443 0.9916613 -0.07410949 0.05753004 0.9955894 -0.08602702 0.08268594 0.9928557 -0.0715999 0.01404869 0.9973346 -0.07802098 -0.03741168 0.9962495 -0.08706313 -0.02442228 0.9959034 -0.06744289 -0.08317482 0.9942502 -0.07401311 -0.1329526 0.9883551 -0.07678002 -0.1302922 0.9884983 -0.05454307 -0.1780546 0.9825078 -0.0618214 -0.2423363 0.9682207 -0.02299612 -0.32164 0.9465828 -0.001624584 -0.3833878 0.923586 0.001960217 -0.385149 0.9228524 0.0292707 -0.4247984 0.9048147 0.04722738 -0.4752256 0.8785956 0.03754478 -0.4720535 0.88077 0.08348286 -0.5429155 0.8356277 0.1320627 -0.5667693 0.8132233 0.1679158 -0.6236424 0.7634622 0.235961 -0.6523265 0.7202726 0.2473261 -0.6683323 0.7015425 0.1948037 -0.6285178 0.7530053 0.1614989 -0.6030445 0.7811885 0.1077732 -0.5429939 0.8327921 -0.02013224 -0.3235968 0.9459809 -0.03820526 -0.267221 0.9628776 -0.05432975 -0.2194398 0.9741122 -0.04178249 0.2610752 0.9644139 -0.1984286 0.9516093 0.2346614 -0.09671318 0.9622653 0.2543464 -0.2976034 0.8863691 0.3546576 -0.2284135 0.9147664 0.3332115 -0.221086 0.9157468 0.3354534 -0.3401812 0.8307386 0.4406248 -0.3361078 0.8321893 0.4410133 -0.4358463 0.7204015 0.5394996 -0.4240865 0.7277022 0.5390735 -0.5131346 0.5836014 0.6293666 -0.4802806 0.6692976 0.5668962 -0.553346 0.5106703 0.6580457 -0.5157051 0.5790857 0.6314334 -0.5118875 0.5826648 0.6312471 -0.5670235 0.4392044 0.6968386 -0.5711665 0.4337471 0.6968731 -0.615547 0.2642971 0.7424615 -0.6116074 0.2767921 0.741163 -0.6122056 0.2638615 0.7453733 -0.6332585 0.1860982 0.7512331 -0.6313284 0.09131813 0.7701205 -0.6387914 -0.06372761 0.7667362 -0.6315796 -0.08786165 0.7703166 -0.6443157 0.02238553 0.764432 -0.6240633 -0.2253924 0.74816 -0.6365221 -0.1417281 0.7581246 -0.6113893 -0.2559516 0.7487937 -0.6033309 -0.3059677 0.7364616 -0.5618072 -0.4471775 0.6959921 -0.598422 -0.3712586 0.7099706 -0.5751433 -0.4304515 0.6956448 -0.5466049 -0.5347667 0.6443972 -0.5046799 -0.5883187 0.6318064 -0.4532722 -0.6999381 0.551934 -0.4984551 -0.6306607 0.5948191 -0.3280064 -0.8368278 0.4383278 -0.3453817 -0.8307456 0.436547 -0.4195789 -0.7568316 0.5011582 -0.2172959 -0.9166364 0.3355002 -0.2954243 -0.8883109 0.3516082 -0.1981589 -0.9532947 0.2279524 -0.1063616 -0.9645107 0.2416739 -0.2331584 -0.9147149 0.3300516 -0.4297179 -0.7191674 0.5460229 -0.575152 -0.4304563 0.6956347 -0.6186294 -0.2643046 0.7398925 -0.6337158 0.1022704 0.7667757 -0.6016197 0.3604477 0.7128332 -0.3996622 0.7845366 0.4741019 0.7660521 -8.04536e-5 0.6427787 0.7660462 -7.01529e-5 0.6427857 0.7661162 1.04804e-4 0.6427022 0.766009 8.98509e-5 0.64283 0.7660216 3.49247e-5 0.642815 0.7660098 -6.49343e-5 0.6428289 0.7660455 3.23362e-5 0.6427863 0.7660965 8.73622e-5 0.6427255 0.7660644 -1.08159e-4 0.642764 0.7660501 4.87506e-5 0.642781 0.7661054 1.29072e-4 0.642715 0.7660132 -1.40013e-4 0.642825 0.7660325 -6.48603e-5 0.6428021 0.7660763 3.2384e-5 0.6427498 0.7661027 -1.05316e-4 0.6427184 0.7660434 -4.26573e-5 0.642789 0.7660133 1.75241e-5 0.6428249 0.7659616 -1.12691e-4 0.6428864 0.7660478 1.62726e-5 0.6427836 0.7660629 -1.61924e-5 0.6427658 0.7660632 8.14095e-6 0.6427652 0.7660026 1.36328e-4 0.6428375 0.7660846 6.99237e-5 0.6427397 0.7661054 -1.29072e-4 0.642715 0.7660411 -1.62728e-5 0.6427916 0.7659989 -4.82205e-5 0.6428419 0.7660687 5.72391e-5 0.6427587 0.766088 1.05319e-4 0.6427357 0.766037 -1.6508e-4 0.6427965 0.7659764 -9.75932e-5 0.6428686 0.766037 1.61054e-4 0.6427965 0.7660324 6.48603e-5 0.642802 0.7660288 -3.05587e-5 0.6428064 0.7660605 8.13988e-5 0.6427687 0.7660847 -6.99238e-5 0.6427397 0.7659764 8.33609e-5 0.6428686 0.7660767 0 0.6427493 0.7659463 -4.18728e-5 0.6429046 0.7660965 -8.73622e-5 0.6427255 0.7661274 -5.05991e-4 0.6426887 0.7659969 0 0.6428443 0.7660131 1.40013e-4 0.6428249 0.7666001 0 0.6421248 0.7659941 1.95307e-4 0.6428475 0.7660026 -1.40725e-4 0.6428375 0.7660654 -1.47684e-5 0.6427627 0.7662099 1.26462e-5 0.6425905 0.7659049 0.001239776 0.6429528 0.7662308 -2.52915e-5 0.6425657 0.7659771 1.12688e-4 0.6428679 0.7660654 7.38419e-6 0.6427627 0.7659826 2.20432e-5 0.6428615 0.637708 -0.1254602 -0.7599924 0.5976281 -0.3681607 -0.7122489 0.5200874 -0.5876504 -0.6198195 0.4096851 -0.7705602 -0.4882571 0.2737168 -0.9048046 -0.3262021 0.1204162 -0.9822971 -0.1435005 -0.04036432 -0.9980263 0.04810768 -0.1986598 -0.9510425 0.2367542 -0.3442984 -0.8443951 0.4104335 -0.468599 -0.6844888 0.5584712 -0.5632946 -0.4817554 0.6712756 -0.6225765 -0.2488202 0.7419482 -0.6423671 -0.03627991 0.7655379 -0.6541696 0 0.756348 -0.6225758 0.2488248 0.7419473 -0.5632947 0.4817554 0.6712756 -0.468599 0.6844888 0.5584712 -0.3443042 0.8443896 0.4104401 -0.1986598 0.9510425 0.2367542 -0.04036432 0.9980263 0.04810786 0.1204162 0.9822971 -0.1435005 0.2737168 0.9048046 -0.3262021 0.4096851 0.7705602 -0.4882571 0.5200874 0.5876505 -0.6198195 0.5976302 0.3681523 -0.7122514 0.6377322 0.1254427 -0.7599749 0.6377091 0.1254459 -0.7599937 0.5976823 0.3681266 -0.712221 0.5201216 0.5876256 -0.6198143 0.4096761 0.7705821 -0.4882304 0.2737062 0.9048085 -0.3261999 0.12043 0.9822929 -0.1435176 -0.04036921 0.9980262 0.04810661 -0.1986115 0.9510602 0.2367235 -0.3444883 0.8442817 0.4105075 -0.4684836 0.6845901 0.558444 -0.563268 0.4817659 0.6712904 -0.6196834 0.236539 0.7483595 -0.6225656 -0.2488158 0.7419587 -0.5632733 -0.481751 0.6712967 -0.4684774 -0.6846004 0.5584365 -0.3444826 -0.8442873 0.4105005 -0.1986115 -0.9510602 0.2367235 -0.04036921 -0.9980262 0.04810649 0.1204277 -0.9822937 -0.1435149 0.2737014 -0.9048122 -0.3261943 0.4096822 -0.7705741 -0.4882379 0.5201157 -0.5876384 -0.6198071 0.5976781 -0.3681435 -0.7122159 0.637732 -0.1254451 -0.7599747 0.7659895 2.12801e-4 0.6428531 0.7660343 -3.72326e-4 0.6427997 0.7663835 -0.001249194 0.6423822 0.7660484 1.33133e-4 0.6427829 0.7660256 -1.03192e-4 0.6428102 0.7663835 0.001249194 0.6423822 0.7660257 1.37589e-4 0.6428101 0.766055 -2.24562e-5 0.642775 0.766052 8.30939e-5 0.6427787 0.765993 -2.19703e-4 0.6428489 0.7660551 2.60637e-5 0.6427749 0.766052 -7.38612e-5 0.6427787 0.7660484 -9.68241e-5 0.6427829 0.7660557 -2.34399e-5 0.6427744 0.7660211 -2.49009e-4 0.6428155 0.7660284 -1.06772e-4 0.6428068 0.7660552 0 0.6427749 0.7660434 -8.23813e-5 0.642789 0.7660191 3.29518e-4 0.6428179 0.7660132 1.77791e-4 0.6428248 0.7660553 -2.77567e-5 0.6427748 0.7660419 1.29086e-4 0.6427906 0.7660558 1.19217e-4 0.6427743 0.3246896 -7.70788e-4 -0.9458204 0.3358917 -0.01087641 -0.9418379 0.3241618 0 -0.9460018 0.3241482 0 -0.9460063 0.3241192 -1.37624e-5 -0.9460163 0.3406013 0.007179558 -0.9401805 0.3240453 0.001523971 -0.9460404 0.5184093 -9.03062e-5 -0.8551327 0.5180831 -2.93405e-5 -0.8553303 0.5179998 3.70933e-5 -0.8553808 0.5183459 -8.76045e-5 -0.8551712 0.5179582 -2.28086e-4 -0.8554059 0.5178057 -3.1136e-4 -0.8554983 0.5184866 0.001680195 -0.8550841 0.518011 2.29102e-5 -0.855374 0.5181626 -1.68756e-4 -0.8552823 0.5179817 -3.7625e-4 -0.8553917 0.518013 -1.46729e-5 -0.8553729 0.517962 6.28696e-5 -0.8554037 0.518022 -3.61874e-5 -0.8553673 0.5182256 -7.49686e-5 -0.8552441 0.517899 -1.87074e-4 -0.8554418 0.5176118 -7.08249e-4 -0.8556153 0.5181996 1.04485e-4 -0.8552598 0.5182473 6.36251e-5 -0.8552308 0.5181614 1.67103e-4 -0.8552829 0.5183478 1.03952e-4 -0.8551699 0.5177251 8.03173e-5 -0.8555471 0.5179848 -3.83295e-5 -0.8553898 0.518369 2.99742e-4 -0.8551571 0.5180855 -4.55133e-4 -0.8553289 0.5182557 2.72336e-5 -0.8552258 0.5181195 -7.5365e-6 -0.8553084 0.5180602 5.74219e-5 -0.8553442 0.5182989 -1.02405e-4 -0.8551996 0.5181624 5.15104e-4 -0.8552822 0.5228573 7.77471e-4 -0.8524199 0.522625 -0.001120924 -0.8525621 0.5179538 -7.48395e-5 -0.8554087 0.5182028 6.15596e-5 -0.8552578 0.5180005 -4.25887e-5 -0.8553804 0.5179423 7.05808e-5 -0.8554157 0.5180274 -3.87132e-5 -0.855364 0.5180326 2.27069e-5 -0.855361 0.5182394 -2.57299e-4 -0.8552356 0.5180245 2.79771e-5 -0.8553658 0.518076 3.11693e-5 -0.8553345 0.5180735 0 -0.8553361 0.5181104 7.16414e-6 -0.8553138 0.832549 -0.5199409 -0.191112 0.726188 -0.6691626 -0.1577103 0.6748726 -0.6769844 -0.2936652 0.5955297 -0.7033821 -0.3880697 0.5146483 -0.7073491 -0.484556 0.4421446 -0.6809034 -0.5838481 0.47042 -0.6988139 -0.5388547 0.3582131 -0.6484256 -0.6717348 0.2866721 -0.5884376 -0.7560161 0.2236993 -0.50899 -0.8311966 0.1708429 -0.4136729 -0.8942525 0.1707768 -0.4134677 -0.8943601 0.1295353 -0.3049839 -0.943507 0.1013428 -0.1872121 -0.977078 0.1013289 -0.1873993 -0.9770435 0.08642083 -0.06275564 -0.9942802 0.08715289 0.06223821 -0.9942489 0.08771556 0.06267917 -0.9941717 0.09693849 0.181965 -0.9785151 0.1013273 0.1872124 -0.9770795 0.1293588 0.3049361 -0.9435467 0.1295182 0.3049702 -0.9435138 0.1708929 0.4138323 -0.8941692 0.1705929 0.4137682 -0.8942561 0.2250704 0.5093904 -0.8305811 0.2234143 0.5091724 -0.8311616 0.2885934 0.5882515 -0.7554297 0.2869488 0.5883003 -0.756018 0.3573324 0.6488308 -0.6718127 0.3579053 0.6487348 -0.6716004 0.4259741 0.6854358 -0.5905285 0.4421753 0.6809017 -0.583827 0.5155143 0.7070174 -0.4841194 0.5146332 0.7073566 -0.4845611 0.5956088 0.7033222 -0.3880568 0.6747844 0.6770818 -0.2936433 0.7559912 0.624538 -0.196035 0.8324746 0.5200518 -0.1911346 0.7261745 0.6691739 -0.1577239 0.6748726 0.6769845 -0.2936648 0.5955382 0.7033766 -0.3880667 0.4703868 0.6988635 -0.5388193 0.1295152 0.3048927 -0.9435392 0.1013289 0.1873993 -0.9770435 0.08718276 -0.06341183 -0.9941721 0.102978 -0.1889947 -0.9765637 0.1293408 -0.3049713 -0.9435378 0.1703895 -0.4134687 -0.8944334 0.2238249 -0.5089921 -0.8311616 0.2865202 -0.5884472 -0.7560662 0.3580526 -0.648486 -0.6717621 0.4243011 -0.685876 -0.5912215 0.5155189 -0.7070195 -0.4841115 0.5956292 -0.7033089 -0.3880495 0.6747843 -0.6770817 -0.2936437 0.7560048 -0.6245229 -0.1960305 0.2359791 0.6523167 -0.7202755 0.2472902 0.6683546 -0.7015338 0.1846525 0.6267691 -0.75701 0.130335 0.5687545 -0.8121152 0.08884578 0.5374665 -0.8385919 0.04703593 0.4752275 -0.8786049 0.03757101 0.4720634 -0.8807637 0.02875292 0.422132 -0.9060784 -0.001570999 0.383386 -0.9235869 -1.65083e-4 0.3840667 -0.9233053 -0.02293509 0.3216246 -0.9465895 -0.0618357 0.2423161 -0.9682248 -0.0545538 0.1781814 -0.9824843 -0.0740574 0.1328725 -0.9883625 -0.07685554 0.1302644 -0.9884961 -0.06748586 0.08315461 -0.994249 -0.07801491 0.03744769 -0.9962487 -0.08710342 0.02443218 -0.9958997 -0.07158964 -0.01404953 -0.9973353 -0.07404482 -0.05757933 -0.9955914 -0.08593672 -0.0827257 -0.9928602 -0.06927043 -0.1086568 -0.9916629 -0.06188791 -0.1616538 -0.9849051 -0.07009905 -0.1848497 -0.9802636 -0.05044513 -0.2137005 -0.975596 -0.04175841 -0.2617943 -0.9642199 -0.04471224 -0.2749256 -0.9604253 -0.01723724 -0.3505128 -0.9363994 -0.0248689 -0.3051765 -0.9519711 0.01194149 -0.4058507 -0.9138613 -0.01195758 -0.3541598 -0.9351085 0.01598834 -0.4081591 -0.9127708 0.04425251 -0.4778348 -0.8773345 0.04081463 -0.4499641 -0.8921135 0.06314045 -0.4881145 -0.8704928 0.09285759 -0.5268357 -0.8448798 0.09888321 -0.5573149 -0.824392 0.1288624 -0.5680495 -0.8128433 0.1713366 -0.6104057 -0.7733361 0.1539719 -0.6090937 -0.7780088 0.2150638 -0.6371341 -0.7401404 0.1881524 -0.6372448 -0.7473405 0.2351458 -0.6539788 -0.7190398 0.2513492 -0.6693918 -0.6990982 -0.05440723 0.2194594 -0.9741034 -0.03812199 0.2672141 -0.9628828 -0.02027904 0.3236029 -0.9459757 0.1042816 0.5392401 -0.8356707 0.1433655 0.5930706 -0.7922839 0.1627051 0.6014729 -0.7821493 0.1948155 0.628535 -0.7529879 -0.0967468 -0.9622721 -0.2543084 -0.1984444 -0.9516006 -0.2346828 -0.2976456 -0.8863484 -0.3546742 -0.2283563 -0.9147851 -0.3331992 -0.2211616 -0.9157367 -0.335431 -0.3401505 -0.8307377 -0.4406501 -0.3361281 -0.8321965 -0.4409841 -0.4358135 -0.7204218 -0.5394989 -0.4240834 -0.727743 -0.539021 -0.5128322 -0.5835651 -0.6296468 -0.4807434 -0.6688039 -0.5670866 -0.5153815 -0.5790188 -0.6317588 -0.5123787 -0.5818836 -0.6315692 -0.5715458 -0.4337924 -0.696534 -0.5664504 -0.4404693 -0.696506 -0.615547 -0.2642341 -0.7424839 -0.6116036 -0.2768777 -0.7411341 -0.6122259 -0.2637752 -0.7453873 -0.633729 -0.1022444 -0.7667683 -0.638773 0.06376791 -0.7667483 -0.6313356 -0.09135067 -0.7701107 -0.6443167 -0.02234005 -0.7644325 -0.6315817 0.08790993 -0.7703093 -0.6240281 0.2254105 -0.7481838 -0.6114088 0.2558484 -0.7488131 -0.6365243 0.1415749 -0.7581513 -0.561856 0.4471527 -0.6959686 -0.598385 0.3713529 -0.7099525 -0.6186861 0.2642187 -0.7398757 -0.6032654 0.3060738 -0.7364712 -0.5466511 0.5347322 -0.6443867 -0.5065643 0.5860515 -0.6324053 -0.500494 0.6267849 -0.5971989 -0.4569489 0.6978965 -0.5514873 -0.4294939 0.7202155 -0.5448161 -0.3279874 0.8368184 -0.4383597 -0.41958 0.7568478 -0.5011328 -0.2172428 0.9166609 -0.3354675 -0.2953994 0.8883149 -0.3516191 -0.198202 0.9532892 -0.2279382 -0.1063951 0.9644847 -0.2417629 -0.233325 0.9146629 -0.3300779 -0.3453783 0.8307443 -0.4365519 -0.5751263 0.4304924 -0.6956337 -0.5751047 0.4305145 -0.6956378 -0.6332091 -0.1861833 -0.7512537 -0.6016392 -0.3604287 -0.7128264 -0.5534633 -0.5104051 -0.6581527 -0.3996918 -0.7845052 -0.4741289 0.766016 5.23784e-5 -0.6428216 0.7661204 6.9833e-5 -0.6426972 0.7659547 -1.62182e-5 -0.6428948 0.7659851 0 -0.6428583 0.766079 -3.25237e-5 -0.6427466 0.7660723 2.43931e-5 -0.6427546 0.7660027 -6.4943e-5 -0.6428376 0.7660553 -3.24999e-5 -0.6427748 0.7660425 4.84142e-5 -0.64279 0.7660405 7.00092e-5 -0.6427924 0.7659976 8.14248e-5 -0.6428436 0.7661644 0 -0.6426448 0.7661486 0 -0.6426635 0.7660629 4.83056e-5 -0.6427656 0.7661374 -3.49559e-5 -0.6426768 0.7660418 3.25007e-5 -0.6427907 0.766101 9.76671e-5 -0.6427204 0.7660724 5.28909e-5 -0.6427544 0.7659477 -3.51127e-5 -0.6429029 0.7661482 3.49552e-5 -0.6426639 0.7661565 -8.85034e-5 -0.6426541 0.7659815 8.7971e-6 -0.6428628 0.7659513 1.62183e-5 -0.6428987 0.7660117 -8.09532e-5 -0.6428266 0.765955 3.51122e-5 -0.6428942 0.7661639 -6.50794e-5 -0.6426452 0.7660008 2.35848e-4 -0.6428396 0.7660008 -2.44584e-4 -0.6428396 0.7661706 6.50786e-5 -0.6426373 0.7660563 -4.83062e-5 -0.6427735 0.7657143 5.12984e-5 -0.643181 0.7660305 -5.2377e-5 -0.6428043 0.7660405 -6.1258e-5 -0.6427924 0.7661276 -6.98321e-5 -0.6426885 0.766043 0 -0.6427895 0.7660027 6.4943e-5 -0.6428376 0.7660228 1.93995e-4 -0.6428135 0.7660428 8.03384e-6 -0.6427896 0.7659915 4.20459e-5 -0.6428509 0.7659914 -5.25573e-5 -0.6428508 0.76599 -7.32833e-5 -0.6428526 0.7660723 -3.52606e-5 -0.6427544 0.7661142 -7.00908e-5 -0.6427046 0.7660118 8.09532e-5 -0.6428265 0.7675803 0 -0.6409529 0.7661565 8.85034e-5 -0.6426541 0.766106 -9.76662e-5 -0.6427144 0.7677224 0 -0.6407828 0.7660292 -4.84154e-5 -0.6428058 0.7657425 -5.55704e-5 -0.6431474 0.7661197 7.00901e-5 -0.6426981 0.7660228 -1.89954e-4 -0.6428135 -0.637732 -0.1254451 -0.7599746 -0.5976278 -0.3678916 -0.7123882 -0.519926 -0.5878 -0.619813 -0.4096922 -0.7705758 -0.4882268 -0.2737313 -0.9047941 -0.3262192 -0.120453 -0.9822861 -0.143545 0.04035586 -0.9980275 0.04809087 0.1986304 -0.9510573 0.2367191 0.3444656 -0.844304 0.4104804 0.4685615 -0.6846125 0.558351 0.56326 -0.4817591 0.6713021 0.6226248 -0.2485278 0.7420057 0.6423246 -0.03676772 0.7655504 0.6311145 0 0.7756897 0.6226232 0.248537 0.7420039 0.5632627 0.4817516 0.6713052 0.4685678 0.6846021 0.5583585 0.3444656 0.8443041 0.4104803 0.1986304 0.9510573 0.2367193 0.04035663 0.9980274 0.04809165 -0.120453 0.9822861 -0.143545 -0.2737362 0.9047906 -0.3262246 -0.409686 0.7705837 -0.4882194 -0.5199201 0.5878128 -0.6198059 -0.5977402 0.3678993 -0.7122898 -0.6377122 0.1254075 -0.7599976 -0.6377323 0.1254428 -0.7599748 -0.5975113 0.3681698 -0.7123422 -0.5200784 0.5876695 -0.619809 -0.4096983 0.7705678 -0.4882341 -0.2737252 0.9048067 -0.3261895 -0.12046 0.9822841 -0.1435527 0.04035419 0.9980275 0.04809165 0.1986432 0.9510481 0.2367458 0.3444768 0.8442819 0.4105169 0.4685115 0.6846337 0.558367 0.5633131 0.4817031 0.6712977 0.6295027 0.2361542 0.7402416 0.6226187 -0.2485644 0.7419984 0.5633158 -0.4816956 0.6713008 0.4685115 -0.6846337 0.5583669 0.3444825 -0.8442763 0.4105234 0.1986432 -0.9510481 0.2367459 0.04035341 -0.9980276 0.04809057 -0.1204577 -0.9822848 -0.14355 -0.27373 -0.9048033 -0.326195 -0.4097045 -0.77056 -0.4882414 -0.5200754 -0.5876758 -0.6198055 -0.5976237 -0.3681775 -0.7122438 -0.637711 -0.1254218 -0.7599961 0.7659456 -1.06411e-4 -0.6429055 0.7661153 -7.44608e-4 -0.6427028 0.7660231 2.74609e-5 -0.6428132 0.7660424 -4.84117e-5 -0.6427901 0.766043 1.5624e-4 -0.6427894 0.766094 -3.08597e-4 -0.6427285 0.7661016 3.43913e-4 -0.6427195 0.7660307 2.06378e-4 -0.642804 0.7660004 -6.46344e-5 -0.6428401 0.7660349 4.14342e-5 -0.6427991 0.766042 -1.19769e-4 -0.6427906 0.7660361 1.0984e-4 -0.6427976 0.7660358 1.1977e-4 -0.642798 0.7659967 7.38684e-5 -0.6428446 0.7666127 0.001014411 -0.642109 0.7660387 4.52728e-5 -0.6427944 0.7660387 -4.52728e-5 -0.6427944 0.7660349 -5.09959e-5 -0.6427991 0.7660388 -1.70137e-4 -0.6427945 0.7660412 6.84661e-5 -0.6427915 0.7660425 8.07164e-5 -0.64279 0.7660371 7.04864e-5 -0.6427963 0.76603 -4.17035e-5 -0.642805 + + + + + + + + + + + + + + +

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

+
+
+
+
+ + + + + 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 + + + + 0.001 0 0 -0.93 0 0.001 0 0 0 0 0.001 -1.32 0 0 0 1 + + + + + + + + + + + + + +
\ No newline at end of file diff --git a/kuka_kr16_support/meshes/kr16_2/visual/link_5.dae b/kuka_kr16_support/meshes/kr16_2/visual/link_5.dae new file mode 100644 index 000000000..22b810098 --- /dev/null +++ b/kuka_kr16_support/meshes/kr16_2/visual/link_5.dae @@ -0,0 +1,100 @@ + + + + + Blender User + Blender 2.74.0 commit date:2015-03-31, commit time:13:39, hash:000dfc0 + + 2015-06-09T10:44:29 + 2015-06-09T10:44:29 + + Z_UP + + + + + + + + + 0 0 0 1 + + + 0 0 0 1 + + + 0.512 0.2088141 0.07027201 1 + + + 0.03125 0.03125 0.03125 1 + + + 1 + + + 1 + + + + + + + + + + + + + + + + 954.4848 70 1365.241 943.999 70 1369.5 939.8731 70 1370.545 949.3594 70 1367.66 932.8354 70 1371.363 928.5809 70 1371.48 938.4686 70 1370.739 934.2529 70 1371.324 945.3735 70 1369.152 950.6873 70 1367.162 927.1679 70 1371.363 963.7855 70 1358.791 960.5001 70 1361.497 967.8477 70 1354.839 964.88 70 1357.89 959.3131 70 1362.272 955.75 70 1364.6 971.4506 70 1350.464 968.8365 70 1353.823 981.2658 70 1324.246 900.6896 70 1362.274 897.2603 70 1359.754 905.5181 70 1365.242 901.8322 70 1363.114 974.5504 70 1345.719 972.3215 70 1349.345 977.1093 70 1340.662 975.2929 70 1344.511 979.0964 70 1335.354 977.7145 70 1339.38 980.4876 70 1329.86 979.5568 70 1334.013 910.6436 70 1367.661 906.746 70 1365.951 980.7976 70 1328.477 898.4028 70 1279.406 956.9371 70 1276.175 960.5001 70 1278.503 951.9525 70 1273.478 955.75 70 1275.4 913.2955 70 1271.346 903.0602 70 1276.177 908.0446 70 1273.479 961.5947 70 1279.405 894.129 70 1283.129 897.2603 70 1280.246 890.2905 70 1287.299 893.0857 70 1284.089 892.1544 70 1354.841 889.3593 70 1351.632 896.217 70 1358.793 893.0857 70 1355.911 916.0042 70 1369.501 911.9421 70 1368.23 921.5346 70 1370.74 917.3575 70 1369.924 922.9263 70 1371.012 946.7015 70 1271.345 950.6873 70 1272.838 917.3575 70 1270.076 906.746 70 1274.049 886.9342 70 1291.866 889.3593 70 1288.368 884.1005 70 1296.774 886.1262 70 1293.031 881.824 70 1301.964 883.4256 70 1298.021 878.7344 70 1324.25 969.7075 70 1287.296 972.3215 70 1290.655 965.8688 70 1283.127 968.8365 70 1286.177 941.2477 70 1269.803 945.3735 70 1270.848 935.6574 70 1268.871 939.8731 70 1269.455 929.9984 70 1268.559 934.2529 70 1268.676 924.3394 70 1268.871 928.5809 70 1268.52 918.7492 70 1269.804 922.9263 70 1268.988 911.9421 70 1271.77 901.8322 70 1276.886 880.1323 70 1307.373 881.2904 70 1303.278 879.046 70 1312.936 879.7465 70 1308.738 888.5513 70 1350.467 981.4218 70 1318.581 981.4218 70 1322.837 980.9536 70 1312.933 981.4218 70 1317.163 978.1749 70 1301.961 979.5568 70 1305.987 975.8981 70 1296.771 977.7145 70 1300.62 973.0641 70 1291.863 975.2929 70 1295.489 878.5781 70 1318.584 878.8126 70 1314.335 878.5 70 1320 880.9046 70 1335.358 879.7465 70 1331.262 882.892 70 1340.665 881.2904 70 1336.722 885.4513 70 1345.722 883.4256 70 1341.979 886.1262 70 1346.969 979.8669 70 1307.37 980.7976 70 1311.523 964.88 70 1282.11 879.5131 70 1329.863 878.8126 70 1325.665 924.3346 74.14392 1268.813 930 74.14392 1268.5 918.7379 74.14392 1269.746 913.278 74.14392 1271.29 908.021 74.14392 1273.426 903.0308 74.14392 1276.126 898.3681 74.14392 1279.359 894.0892 74.14392 1283.086 890.2463 74.14392 1287.26 886.8859 74.14392 1291.832 884.0489 74.14392 1296.746 881.7697 74.14392 1301.942 880.0759 74.14392 1307.358 878.9881 74.14392 1312.926 878.5195 74.14392 1318.581 878.6759 74.14392 1324.253 879.4553 74.14392 1329.873 880.8482 74.14392 1335.374 882.8377 74.14392 1340.687 885.3997 74.14392 1345.75 888.5031 74.14392 1350.5 892.1102 74.14392 1354.88 896.1773 74.14392 1358.837 900.6549 74.14392 1362.322 905.4887 74.14392 1365.293 910.6201 74.14392 1367.714 915.9867 74.14392 1369.557 921.5234 74.14392 1370.798 927.163 74.14392 1371.422 932.837 74.14392 1371.422 938.4766 74.14392 1370.798 944.0133 74.14392 1369.557 949.38 74.14392 1367.714 954.5113 74.14392 1365.293 959.3451 74.14392 1362.322 963.8228 74.14392 1358.837 967.8898 74.14392 1354.88 971.4969 74.14392 1350.5 974.6004 74.14392 1345.75 977.1624 74.14392 1340.687 979.1519 74.14392 1335.374 980.5447 74.14392 1329.873 981.3241 74.14392 1324.253 981.5 74.14392 1320 981.4805 74.14392 1318.581 981.0119 74.14392 1312.926 979.9241 74.14392 1307.358 978.2304 74.14392 1301.942 975.9511 74.14392 1296.746 973.1141 74.14392 1291.832 969.7537 74.14392 1287.26 965.9108 74.14392 1283.086 961.632 74.14392 1279.359 956.9692 74.14392 1276.126 951.979 74.14392 1273.426 946.7221 74.14392 1271.29 941.2621 74.14392 1269.746 935.6654 74.14392 1268.813 913.44 74.14392 1379.997 984.8059 74.14392 1362.833 965.9382 74.14392 1371.603 947.0848 74.14392 1379.997 896.369 74.14392 1372.926 876.5111 74.14392 1353.068 869.44 74.14392 1335.997 869.44 74.14392 1303.997 876.5111 74.14392 1286.926 896.369 74.14392 1267.068 965.9382 74.14392 1268.391 984.8059 74.14392 1277.161 947.0848 74.14392 1259.997 913.44 74.14392 1259.997 991.8169 74.14392 1273.892 991.8169 74.14392 1366.102 913.44 94.603 1379.997 896.369 94.603 1372.926 880.9509 99.42051 1357.508 876.5111 97.80455 1353.068 869.44 95.2309 1303.997 876.5111 97.80455 1286.926 869.44 95.2309 1335.997 880.9509 99.42051 1282.486 896.369 94.603 1267.068 913.44 94.603 1259.997 899.44 106.15 1352.55 899.44 106.15 1287.444 917.4183 106.15 1359.997 947.0848 94.603 1379.997 917.4183 106.15 1279.997 947.0848 94.603 1259.997 942.8338 106.15 1279.997 965.9382 94.603 1268.391 959.4 106.15 1287.373 996.2606 90.88184 1274.836 942.8338 106.15 1359.997 959.4 106.15 1352.621 965.9382 94.603 1371.603 996.2606 90.88184 1365.158 1014.224 44.57946 1278.654 1009.613 44.57946 1280.804 1009.613 44.57946 1359.189 1014.224 44.57946 1361.339 1005.211 24.72321 1282.857 1005.211 24.72321 1357.137 976.6562 -13.86698 1296.172 976.6562 -13.86698 1343.821 970.94 -39.651 1298.838 970.94 -39.651 1341.156 1014.224 -49 1278.654 970.94 -49 1298.838 1014.224 -49 1361.339 970.94 -49 1341.156 1015.455 -49 1361.078 1015.455 75.09497 1361.078 1002.078 88.47233 1363.921 1002.078 88.47233 1276.073 1015.455 75.09497 1278.916 1015.455 -49 1278.916 1007.55 83 1286 1007.55 83 1331 1041.4 49.15 1366.121 1041.4 49.15 1273.873 1002.078 88.47233 1286 1002.078 88.47233 1331 1041.4 47.01652 1313.237 1041.4 45.93947 1307.921 1041.4 40.67658 1344.526 1041.4 43.20752 1339.729 1041.4 39.20991 1293.186 1041.4 35.8981 1288.891 1041.4 44.26354 1302.764 1041.4 47.32575 1324.062 1041.4 47.48063 1318.64 1041.4 45.17518 1334.675 1041.4 34.06376 1353.101 1041.4 37.61536 1349.003 1041.4 32.11831 1285.002 1041.4 27.9198 1281.569 1041.4 42.01056 1297.83 1041.4 46.55392 1329.43 1041.4 18.49033 1276.244 1041.4 13.3823 1274.421 1041.4 23.35731 1278.636 1041.4 25.68044 1359.956 1041.4 30.06809 1356.769 1041.4 11.35011 1366.121 1041.4 15.96235 1364.734 1041.4 20.958 1362.623 1041.4 11.35011 1273.873 995 83 1286 995 91.404 1286 995 83 1331 995 91.404 1331 992 92.64664 1289 992 92.64664 1328 992 83 1328 992 83 1289 998.2275 83 1295.878 998.2275 83 1321.122 999 83 1321 999.7725 83 1321.122 999.7725 83 1295.878 999 83 1296 996.6224 83 1322.727 997.5305 83 1325.523 999.7725 83 1325.878 999 83 1326 996.6224 83 1294.273 1000.469 83 1295.523 996.9775 83 1322.031 997.5305 83 1321.477 996.5 83 1323.5 996.9775 83 1324.969 996.6224 83 1324.273 998.2275 83 1325.878 996.9775 83 1294.969 997.5305 83 1295.523 999 83 1291 996.9775 83 1292.031 997.5305 83 1291.477 1000.469 83 1325.523 1001.378 83 1322.727 1001.5 83 1323.5 1001.5 83 1293.5 1001.378 83 1294.273 998.2275 83 1291.122 996.5 83 1293.5 996.6224 83 1292.727 1001.378 83 1324.273 1001.023 83 1294.969 1001.023 83 1322.031 1000.469 83 1321.477 1001.378 83 1292.727 999.7725 83 1291.122 1001.023 83 1324.969 1001.023 83 1292.031 1000.469 83 1291.477 1001.378 73 1292.727 1001.5 73 1293.5 1001.023 73 1292.031 1000.469 73 1291.477 999.7725 73 1291.122 999 73 1291 998.2275 73 1291.122 997.5305 73 1291.477 996.9775 73 1292.031 996.6224 73 1292.727 996.5 73 1293.5 996.6224 73 1294.273 996.9775 73 1294.969 997.5305 73 1295.523 998.2275 73 1295.878 999 73 1296 999.7725 73 1295.878 1000.469 73 1295.523 1001.023 73 1294.969 1001.378 73 1294.273 1001.378 73 1322.727 1001.5 73 1323.5 1001.023 73 1322.031 1000.469 73 1321.477 999.7725 73 1321.122 999 73 1321 998.2275 73 1321.122 997.5305 73 1321.477 996.9775 73 1322.031 996.6224 73 1322.727 996.5 73 1323.5 996.6224 73 1324.273 996.9775 73 1324.969 997.5305 73 1325.523 998.2275 73 1325.878 999 73 1326 999.7725 73 1325.878 1000.469 73 1325.523 1001.023 73 1324.969 1001.378 73 1324.273 1026.378 -49 1363.201 1041.4 -11.35011 1366.121 1041.4 -49.5 1366.121 1026.378 -49.5 1363.201 1041.4 -5.414592 1367.187 1041.4 0 1367.497 1041.4 5.414592 1367.187 1041.4 10.7586 1366.262 1041.4 -10.7586 1366.262 1030.317 -49.5 1361.569 1041.4 -49.5 1350.486 1010.736 -49 1369.68 1010.736 -71 1369.68 1030.317 -71 1361.569 962.6395 -49 1379.247 962.6395 -71 1379.247 913.6395 -49 1379.247 913.6395 -71 1379.247 896.5684 -49 1372.176 896.5684 -71 1372.176 877.7105 -49 1353.318 877.7105 -71 1353.318 870.6395 -49 1336.247 870.6395 -71 1336.247 870.6395 -49 1303.747 870.6395 -71 1303.747 877.7105 -49 1286.676 877.7105 -71 1286.676 896.5684 -71 1267.818 896.5684 -49 1267.818 913.6395 -49 1260.747 913.6395 -71 1260.747 962.6395 -49 1260.747 962.6395 -71 1260.747 1010.736 -49 1270.314 1010.736 -71 1270.314 895.6733 -49 1323.453 895.5193 -49 1318.847 954.7994 -49 1343.984 951.3814 -49 1347.076 903.654 -49 1297.726 906.8579 -49 1294.413 897.049 -49 1309.778 898.7054 -49 1305.478 896.4398 -49 1327.998 899.7453 -49 1336.58 897.8053 -49 1332.4 957.7749 -49 1340.465 956.346 -49 1297.726 959.0798 -49 1301.436 914.4401 -49 1289.208 900.9202 -49 1301.436 895.9806 -49 1314.262 947.5818 -49 1349.684 960.2548 -49 1336.58 961.2946 -49 1305.478 962.9511 -49 1309.778 953.1421 -49 1294.413 945.5599 -49 1289.208 910.4749 -49 1291.557 908.6187 -49 1347.076 905.2006 -49 1343.984 963.5602 -49 1327.998 962.1948 -49 1332.4 941.3168 -49 1287.409 912.4182 -49 1349.684 916.5316 -49 1351.762 925.4016 -49 1354.192 920.8853 -49 1353.274 943.4685 -49 1351.762 939.1148 -49 1353.274 949.5252 -49 1291.557 936.872 -49 1286.191 927.6957 -49 1285.577 932.3043 -49 1285.577 918.6832 -49 1287.409 923.1281 -49 1286.191 902.2251 -49 1340.465 930 -49 1354.5 964.4807 -49 1318.847 964.3267 -49 1323.453 964.0194 -49 1314.262 934.5984 -49 1354.192 1026.378 -49 1276.793 930.002 -46.5 1354.442 926.5467 -46.5 1354.327 925.4112 -46.5 1354.135 922.0022 -46.5 1353.56 920.9024 -46.5 1353.219 917.6005 -46.5 1352.195 916.5559 -46.5 1351.71 913.4199 -46.5 1350.255 912.4494 -46.5 1349.635 909.5353 -46.5 1347.775 908.656 -46.5 1347.031 906.0159 -46.5 1344.799 905.2434 -46.5 1343.945 902.9244 -46.5 1341.381 902.2727 -46.5 1340.432 900.3162 -46.5 1337.582 899.7968 -46.5 1336.554 898.2376 -46.5 1333.468 897.8599 -46.5 1332.381 896.7258 -46.5 1329.115 896.4965 -46.5 1327.986 895.8078 -46.5 1324.598 895.7309 -46.5 1323.449 895.5 -46.5 1320 895.5769 -46.5 1318.851 895.8078 -46.5 1315.402 896.0372 -46.5 1314.273 896.7258 -46.5 1310.885 897.1036 -46.5 1309.797 898.2376 -46.5 1306.532 898.757 -46.5 1305.504 900.3162 -46.5 1302.418 900.9678 -46.5 1301.469 902.9244 -46.5 1298.619 903.6968 -46.5 1297.765 906.0159 -46.5 1295.201 906.8952 -46.5 1294.457 909.5353 -46.5 1292.225 910.5059 -46.5 1291.605 913.4199 -46.5 1289.745 914.4645 -46.5 1289.26 917.6005 -46.5 1287.805 918.7003 -46.5 1287.464 922.0022 -46.5 1286.44 923.1377 -46.5 1286.248 926.5467 -46.5 1285.673 927.6976 -46.5 1285.635 931.1528 -46.5 1285.519 932.2986 -46.5 1285.635 935.7384 -46.5 1285.981 936.8585 -46.5 1286.248 940.2215 -46.5 1287.049 941.2961 -46.5 1287.463 944.5223 -46.5 1288.705 945.5321 -46.5 1289.259 948.5639 -46.5 1290.92 949.4909 -46.5 1291.603 952.2742 -46.5 1293.654 953.1019 -46.5 1294.455 955.587 -46.5 1296.858 956.3007 -46.5 1297.762 958.4432 -46.5 1300.475 959.0301 -46.5 1301.466 960.7919 -46.5 1304.44 961.2415 -46.5 1305.5 962.5911 -46.5 1308.683 962.8953 -46.5 1309.794 963.8087 -46.5 1313.128 963.9622 -46.5 1314.269 964.423 -46.5 1317.696 964.423 -46.5 1318.847 964.423 -46.5 1322.304 964.2695 -46.5 1323.446 963.8087 -46.5 1326.872 963.5045 -46.5 1327.983 962.5911 -46.5 1331.317 962.1416 -46.5 1332.377 960.7919 -46.5 1335.56 960.2051 -46.5 1336.551 958.4432 -46.5 1339.525 957.7296 -46.5 1340.429 955.587 -46.5 1343.142 954.7593 -46.5 1343.943 952.2742 -46.5 1346.346 951.3471 -46.5 1347.029 948.5639 -46.5 1349.08 947.554 -46.5 1349.633 944.5223 -46.5 1351.295 943.4477 -46.5 1351.708 940.2215 -46.5 1352.951 939.1014 -46.5 1353.218 935.7384 -46.5 1354.019 934.5926 -46.5 1354.135 931.1528 -46.5 1354.481 1041.4 -11.35011 1273.873 1041.4 -49.5 1273.873 1026.378 -49.5 1276.793 1041.4 -8.099804 1273.192 1041.4 8.099804 1273.192 1041.4 2.711719 1272.574 1041.4 -2.711719 1272.574 1030.317 -71 1278.425 1030.317 -49.5 1278.425 1041.4 -49.5 1289.507 1041.4 -49 1350.486 1041.4 -40.67658 1344.526 1041.4 -37.61536 1349.003 1041.4 -49 1289.507 1041.4 -45.93947 1307.921 1041.4 -47.01652 1313.237 1041.4 -43.20752 1339.729 1041.4 -47.32575 1324.062 1041.4 -46.55392 1329.43 1041.4 -47.48063 1318.64 1041.4 -44.26354 1302.764 1041.4 -45.17518 1334.675 1041.4 -42.01056 1297.83 1041.4 -35.8981 1288.891 1041.4 -39.20991 1293.186 1041.4 -18.49033 1276.244 1041.4 -23.35731 1278.636 1041.4 -27.9198 1281.569 1041.4 -32.11831 1285.002 1041.4 -34.06376 1353.101 1041.4 -30.06809 1356.769 1041.4 -13.3823 1274.421 1041.4 -25.68044 1359.956 1041.4 -20.958 1362.623 1041.4 -15.96235 1364.734 1043.568 -49 1291.676 1043.568 -71 1291.676 1043.568 -71 1348.318 1043.568 -49 1348.318 1050.639 -49 1331.247 1050.639 -49 1308.747 1050.639 -71 1331.247 1050.639 -71 1308.747 1052.4 -5.414592 1367.187 1052.4 0 1367.497 1052.4 -10.7586 1366.262 1052.4 -15.96235 1364.734 1052.4 -20.958 1362.623 1052.4 -25.68044 1359.956 1052.4 -30.06809 1356.769 1052.4 -34.06376 1353.101 1052.4 -37.61536 1349.003 1052.4 -40.67658 1344.526 1052.4 -43.20752 1339.729 1052.4 -45.17518 1334.675 1052.4 -46.55392 1329.43 1052.4 -47.32575 1324.062 1052.4 -47.48063 1318.64 1052.4 -47.01652 1313.237 1052.4 -45.93947 1307.921 1052.4 -44.26354 1302.764 1052.4 -42.01056 1297.83 1052.4 -39.20991 1293.186 1052.4 -35.8981 1288.891 1052.4 -32.11831 1285.002 1052.4 -27.9198 1281.569 1052.4 -23.35731 1278.636 1052.4 -18.49033 1276.244 1052.4 -13.3823 1274.421 1052.4 -8.099804 1273.192 1052.4 -2.711719 1272.574 1052.4 2.711719 1272.574 1052.4 8.099804 1273.192 1052.4 13.3823 1274.421 1052.4 18.49033 1276.244 1052.4 23.35731 1278.636 1052.4 27.9198 1281.569 1052.4 32.11831 1285.002 1052.4 35.8981 1288.891 1052.4 39.20991 1293.186 1052.4 42.01056 1297.83 1052.4 44.26354 1302.764 1052.4 45.93947 1307.921 1052.4 47.01652 1313.237 1052.4 47.48063 1318.64 1052.4 47.32575 1324.062 1052.4 46.55392 1329.43 1052.4 45.17518 1334.675 1052.4 43.20752 1339.729 1052.4 40.67658 1344.526 1052.4 37.61536 1349.003 1052.4 34.06376 1353.101 1052.4 30.06809 1356.769 1052.4 25.68044 1359.956 1052.4 20.958 1362.623 1052.4 15.96235 1364.734 1052.4 10.7586 1366.262 1052.4 5.414592 1367.187 1052.4 -37.32672 1316.396 1052.4 35.19256 1307.046 1052.4 33.24747 1302.652 1052.4 36.55979 1311.652 1052.4 -14.07251 1354.756 1052.4 -9.512047 1356.27 1052.4 -18.40191 1352.671 1052.4 -37.48073 1321.199 1052.4 -36.55979 1311.652 1052.4 37.32672 1316.396 1052.4 37.48073 1321.199 1052.4 37.01932 1325.982 1052.4 35.95004 1330.667 1052.4 34.29047 1335.176 1052.4 32.06785 1339.437 1052.4 14.07251 1354.756 1052.4 9.512047 1356.27 1052.4 0 1357.497 1052.4 -4.795393 1357.189 1052.4 -35.19256 1307.046 1052.4 -33.24747 1302.652 1052.4 -30.75646 1298.542 1052.4 18.40191 1352.671 1052.4 22.42914 1350.05 1052.4 4.795393 1357.189 1052.4 -29.31868 1343.378 1052.4 -32.06785 1339.437 1052.4 -34.29047 1335.176 1052.4 -35.95004 1330.667 1052.4 -37.01932 1325.982 1052.4 -16.27064 1286.211 1052.4 20.45756 1288.569 1052.4 16.27064 1286.211 1052.4 29.31868 1343.378 1052.4 26.0881 1346.935 1052.4 -22.42915 1350.05 1052.4 -27.76043 1294.786 1052.4 -24.30857 1291.443 1052.4 -20.45756 1288.569 1052.4 24.30857 1291.443 1052.4 30.75646 1298.542 1052.4 -26.0881 1346.935 1052.4 27.76043 1294.786 1052.4 -11.81656 1284.407 1052.4 -7.168448 1283.188 1052.4 11.81656 1284.407 1052.4 7.168448 1283.188 1052.4 -2.402633 1282.574 1052.4 0 1282.497 1052.4 2.402633 1282.574 1076 -4.795393 1357.189 1076 0 1357.497 1076 -9.512047 1356.27 1076 -14.07251 1354.756 1076 -18.40191 1352.671 1076 -22.42915 1350.05 1076 -26.0881 1346.935 1076 -29.31868 1343.378 1076 -32.06785 1339.437 1076 -34.29047 1335.176 1076 -35.95004 1330.667 1076 -37.01932 1325.982 1076 -37.48073 1321.199 1076 -37.32672 1316.396 1076 -36.55979 1311.652 1076 -35.19256 1307.046 1076 -33.24747 1302.652 1076 -30.75646 1298.542 1076 -27.76043 1294.786 1076 -24.30857 1291.443 1076 -20.45756 1288.569 1076 -16.27064 1286.211 1076 -11.81656 1284.407 1076 -7.168448 1283.188 1076 -2.402633 1282.574 1076 2.402633 1282.574 1076 0 1282.497 1076 7.168448 1283.188 1076 11.81656 1284.407 1076 16.27064 1286.211 1076 20.45756 1288.569 1076 24.30857 1291.443 1076 27.76043 1294.786 1076 30.75646 1298.542 1076 33.24747 1302.652 1076 35.19256 1307.046 1076 36.55979 1311.652 1076 37.32672 1316.396 1076 37.48073 1321.199 1076 37.01932 1325.982 1076 35.95004 1330.667 1076 34.29047 1335.176 1076 32.06785 1339.437 1076 29.31868 1343.378 1076 26.0881 1346.935 1076 22.42914 1350.05 1076 18.40191 1352.671 1076 14.07251 1354.756 1076 9.512047 1356.27 1076 4.795393 1357.189 1029.017 -71 1360.159 1009.436 -71 1368.269 961.3394 -71 1377.836 915.3394 -71 1377.836 898.2684 -71 1370.765 879.4105 -71 1351.907 1009.436 -71 1271.903 961.3394 -71 1262.336 1029.017 -71 1280.014 1049.339 -71 1310.336 1042.268 -71 1293.265 1049.339 -71 1329.836 872.3394 -71 1305.336 879.4105 -71 1288.265 1042.268 -71 1346.907 872.3394 -71 1334.836 915.3394 -71 1262.336 898.2684 -71 1269.407 872.3394 -84.62178 1305.336 872.3394 -84.62178 1334.836 1049.339 -83.28204 1329.836 1049.339 -83.28204 1310.336 1042.268 -85.17672 1346.907 1042.268 -85.17672 1293.265 1029.017 -83.41851 1280.014 1009.436 -81.2453 1271.903 961.3394 -81.6081 1262.336 1041.58 -85.36106 1292.577 1029.932 -83.81516 1280.929 983.4554 -89.93393 1282.161 935.593 -84.62178 1262.336 915.3394 -84.62178 1262.336 1009.436 -81.2453 1368.269 1029.017 -83.41851 1360.159 961.3394 -81.6081 1377.836 1029.932 -83.81516 1359.244 1041.58 -85.36106 1347.595 1028.658 -88.82362 1340.414 1028.658 -88.82362 1299.759 983.4554 -89.93393 1358.011 935.593 -84.62178 1377.836 915.3394 -84.62178 1377.836 1005.815 -91.83097 1300.365 982.8267 -91.95365 1289.699 1005.815 -91.83097 1339.808 982.8267 -91.95365 1350.473 989.3394 -94 1331.713 989.3394 -94 1308.46 967.283 -94 1297.336 967.283 -94 1342.836 922.3014 -94 1297.336 898.2684 -84.62178 1269.407 922.3014 -94 1342.836 898.2684 -84.62178 1370.765 879.4105 -84.62178 1288.265 918.0943 -94 1299.079 879.4105 -84.62178 1351.907 918.0943 -94 1341.094 907.3394 -94 1327.874 909.0821 -94 1332.081 907.3394 -94 1312.298 909.0821 -94 1308.091 + + + + + + + + + + 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 -0.0550915 0.01416021 -0.998381 0.02754443 -0.0141434 -0.9995205 -0.1645639 0.01414924 -0.9862649 -0.08263468 -0.01412731 -0.9964798 -0.2720788 0.01413679 -0.9621711 -0.1916995 -0.0141642 -0.9813515 -0.376281 0.01415753 -0.9263974 -0.2984387 -0.01416498 -0.9543237 -0.4758852 0.01414549 -0.8793937 -0.4016523 -0.01415199 -0.9156829 -0.5697576 0.014131 -0.8216913 -0.5000053 -0.01415348 -0.8659068 -0.6566887 0.01413726 -0.7540293 -0.5922203 -0.01414775 -0.8056519 -0.73565 0.01415151 -0.677214 -0.6771853 -0.0141648 -0.7356761 -0.805683 0.01415383 -0.5921779 -0.754035 -0.01414531 -0.6566819 -0.8659356 0.01414024 -0.4999555 -0.8216974 -0.01415973 -0.5697481 -0.9156826 0.01414579 -0.4016531 -0.8793901 -0.01415503 -0.4758915 -0.9543105 0.01414966 -0.2984815 -0.9263906 -0.01416373 -0.3762978 -0.9813529 0.01415491 -0.1916928 -0.9621681 -0.01415067 -0.2720892 -0.9964846 0.01414865 -0.08257251 -0.9862625 -0.01415407 -0.1645779 -0.9995202 0.01414752 0.02755647 -0.9983808 -0.01416057 -0.05509257 -0.9904226 0.01415562 0.1373417 -0.9983811 -0.01414424 0.05509257 -0.9693043 0.0141623 0.2454559 -0.9862695 -0.01415407 0.164536 -0.9364173 0.01415342 0.3506026 -0.9621791 -0.01415872 0.2720493 -0.892163 0.01415675 0.4514917 -0.9264057 -0.01415264 0.3762608 -0.837084 0.01414901 0.5468915 -0.8793901 -0.01415503 0.4758915 -0.7718395 0.01415562 0.6356598 -0.8216975 -0.01414763 0.5697482 -0.697235 0.01414656 0.716703 -0.7540349 -0.01415354 0.6566818 -0.6141384 0.01412969 0.7890719 -0.6771853 -0.0141648 0.7356761 -0.5236188 0.01414948 0.8518351 -0.5921643 -0.01414775 0.805693 -0.4267466 0.01414799 0.9042605 -0.4999592 -0.01415348 0.8659332 -0.3246537 0.01415383 0.9457271 -0.4016523 -0.01415199 0.9156829 -0.2186667 0.01415008 0.975697 -0.298451 -0.01413691 0.9543203 -0.1099895 0.01414322 0.9938322 -0.1916995 -0.0141642 0.9813515 0 0.01416772 0.9998996 -0.08255273 -0.01412856 0.9964865 0.1099895 0.01415878 0.9938319 0.02754443 -0.01414382 0.9995205 0.2186667 0.01416558 0.9756968 0.1372965 -0.01415455 0.9904288 0.3246537 0.01415848 0.945727 0.2454977 -0.01412695 0.9692941 0.4267466 0.01415395 0.9042605 0.3506024 -0.01415336 0.9364175 0.5236187 0.01416796 0.851835 0.4514849 -0.01413434 0.8921669 0.6141381 0.01416313 0.7890715 0.5468735 -0.01414161 0.8370959 0.6972351 0.01413977 0.7167031 0.6356858 -0.01415574 0.7718181 0.7718395 0.01415592 0.6356598 0.716696 -0.01415371 0.697242 0.8370791 0.01414346 0.546899 0.7890809 -0.01414638 0.6141265 0.8921676 0.01414149 0.4514831 0.8518359 -0.0141626 0.5236173 0.9364173 0.0141533 0.3506026 0.9042643 -0.01415097 0.4267387 0.9693043 0.01415586 0.245456 0.9457183 -0.01415377 0.3246791 0.9904226 0.01415354 0.1373417 0.9757031 -0.01414185 0.2186401 0.9991011 0.009441137 0.04132449 0.9938293 -0.01415097 0.1100142 0.9998052 -0.01415163 -0.01376074 0.9964846 0.01415002 -0.08257251 0.9998999 -0.014153 0 0.9813531 0.01414465 -0.1916928 0.9938293 -0.01415097 -0.1100142 0.9543105 0.01415222 -0.2984815 0.9757029 -0.01415622 -0.21864 0.9156826 0.01414638 -0.4016531 0.9457225 -0.01415377 -0.324667 0.8659356 0.0141372 -0.4999555 0.9042641 -0.01416355 -0.4267386 0.8056831 0.01414167 -0.5921781 0.8518359 -0.0141626 -0.5236173 0.73565 0.0141564 -0.677214 0.78906 -0.01414638 -0.6141533 0.6566886 0.01415055 -0.7540292 0.7166961 -0.01414316 -0.6972422 0.5697574 0.01415586 -0.821691 0.6356858 -0.01415574 -0.7718181 0.4758851 0.0141505 -0.8793936 0.5469334 -0.01417434 -0.8370561 0.376281 0.01416438 -0.9263973 0.4514849 -0.01413434 -0.8921669 0.2720787 0.01414823 -0.9621709 0.3506024 -0.01415336 -0.9364175 0.1645638 0.0141614 -0.9862647 0.2454976 -0.01415908 -0.9692937 0.0550915 0.01416015 -0.998381 0.1373024 -0.0141254 -0.9904285 0.02756011 -0.0141434 -0.9995201 0.1373409 -0.0141254 -0.9904231 0.245459 -0.01415908 -0.9693036 0.3505979 -0.01415336 -0.9364191 0.4514884 -0.01413434 -0.8921651 0.5468772 -0.01417434 -0.8370928 0.6356596 -0.01415574 -0.7718396 0.7167126 -0.01414316 -0.6972253 0.7890686 -0.01414638 -0.6141422 0.8518322 -0.0141626 -0.5236232 0.9042646 -0.01416355 -0.4267374 0.9457227 -0.01415377 -0.3246665 0.9756988 -0.01415622 -0.2186589 0.9938312 -0.01415097 -0.1099971 0.999822 -0.01886427 0 0.9938312 -0.01415097 0.1099971 0.9756988 -0.01414185 0.2186589 0.945724 -0.01415377 0.3246625 0.9042648 -0.01415097 0.4267375 0.8518322 -0.0141626 0.5236232 0.7890617 -0.01414638 0.6141512 0.7167124 -0.01415371 0.6972252 0.6356596 -0.01415574 0.7718396 0.5468975 -0.01414161 0.8370801 0.4514884 -0.01413434 0.8921651 0.3505979 -0.01415336 0.9364191 0.2454591 -0.01412695 0.9693039 0.1373428 -0.01415455 0.9904224 0.02756011 -0.01414382 0.9995201 -0.08259332 -0.01412856 0.9964832 -0.1916879 -0.0141642 0.9813537 -0.2984828 -0.01413691 0.9543103 -0.4016706 -0.01415199 0.9156749 -0.499948 -0.01415348 0.8659399 -0.5921825 -0.01414775 0.8056797 -0.6772156 -0.0141648 0.7356482 -0.7540271 -0.01415354 0.6566907 -0.8217003 -0.01414763 0.5697441 -0.8793795 -0.01415503 0.4759112 -0.9263998 -0.01415264 0.3762755 -0.962168 -0.01415872 0.2720885 -0.986261 -0.01415407 0.1645871 -0.9983819 -0.01414424 0.05507689 -0.9983817 -0.01416057 -0.05507689 -0.9862633 -0.01415407 -0.1645731 -0.962172 -0.01415067 -0.2720753 -0.9264046 -0.01416373 -0.3762632 -0.8793795 -0.01415503 -0.4759112 -0.8217002 -0.01415973 -0.5697441 -0.7540272 -0.01414531 -0.6566908 -0.6772156 -0.0141648 -0.7356482 -0.5921639 -0.01414775 -0.8056934 -0.4999326 -0.01415348 -0.8659486 -0.4016706 -0.01415199 -0.9156749 -0.2984867 -0.01416498 -0.9543086 -0.1916879 -0.0141642 -0.9813537 -0.08256602 -0.01412731 -0.9964855 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 -0.3826828 0 0.9238798 -0.3826828 0 0.9238798 -0.7071068 0 0.7071068 -0.7071068 0 0.7071068 -0.7071068 0 0.7071068 -0.9238799 0 -0.3826829 -0.9238798 0 -0.3826828 -1 0 0 -1 0 0 -0.9238798 0 0.3826828 -0.9238799 0 0.3826829 -0.7071068 0 -0.7071068 -0.7071068 0 -0.7071068 -0.7071068 0 -0.7071068 -0.3826828 0 -0.9238798 -0.3826828 0 -0.9238798 -0.3420201 0.9396926 0 -0.3420201 0.9396926 0 -0.3420199 0.9396927 3.26633e-7 -0.3420199 0.9396927 -3.78781e-7 -0.34202 0.9396927 -3.26633e-7 -0.3420199 0.9396927 3.78783e-7 -0.1913404 0.8660251 0.4619407 -0.1913433 0.8660248 0.4619401 -0.1913413 0.8660255 0.4619396 0 0 1 0 0 1 -0.1913412 0.8660262 -0.4619385 -0.1913413 0.8660255 -0.4619396 -0.1913425 0.8660261 -0.4619382 0 0 -1 0 0 -1 0 0.8660254 -0.5 0 0.8660254 -0.5 0.4067366 0 -0.9135455 0.4067366 0 -0.9135455 0.2033684 0.8660253 -0.4567729 0.2033693 0.8660259 -0.4567713 0.2033696 0.8660259 -0.4567712 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0.2033675 0.8660248 0.4567742 0.2033684 0.8660253 0.4567729 0.2033679 0.8660247 0.456774 0 0.8660254 0.5 0 0.8660254 0.5 0.4067366 0 0.9135455 0.4067366 0 0.9135455 -0.3830229 -0.4226174 -0.8213939 -0.3830233 -0.4226176 -0.8213936 -0.3830228 -0.4226204 0.8213924 -0.3830223 -0.4226202 0.8213928 -0.7660441 -0.642788 0 -0.7660441 -0.642788 0 -0.9762958 0.2164402 0 -0.9762958 0.2164403 0 -0.8038569 0.5948228 0 -0.8038569 0.5948228 0 -0.976296 0.2164399 0 -0.976296 0.2164399 0 -0.4226199 -4.84829e-7 -0.9063071 -0.422621 0 -0.9063066 -0.4226198 0 -0.9063072 -0.4226192 2.62153e-7 -0.9063073 -0.4226188 -1.23681e-6 -0.9063075 -0.4226166 6.70887e-7 0.9063086 -0.4226179 -1.02878e-6 0.9063081 -0.4226188 -1.23681e-6 0.9063075 -0.422621 0 0.9063066 -0.4226176 0 0.9063081 -1 0 0 -1 0 0 0.2079457 0 0.9781404 0.2079156 1.27524e-6 0.9781469 0.2079087 0 0.9781484 0.2079156 -9.41517e-7 0.9781468 0.2079113 2.26146e-6 0.9781477 0.2079106 2.47061e-6 0.9781479 0.2079457 0 0.9781404 0.2079142 1.45602e-6 -0.9781471 0.2079106 2.78485e-6 -0.9781478 0.2079457 0 -0.9781404 0.2079131 0 -0.9781473 0.2079457 0 -0.9781404 0.2079107 1.47925e-6 -0.9781478 0.2079113 2.26146e-6 -0.9781477 0.7071068 0.7071068 0 0.7071078 0.7071059 -5.07941e-7 0.7071063 0.7071073 0 0.7071092 0.7071043 0 0.7071093 0.7071043 0 0.7071076 0.7071061 1.84057e-6 0.7071065 0.7071071 0 0.7071062 0.7071074 2.91415e-7 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 0 0 1 0 0 1 0 0 -1 0 0 -1 0.3826826 0.9238799 0 0.3826837 0.9238795 1.23562e-6 0.3826836 0.9238794 2.40476e-7 0.3826837 0.9238793 0 0.3826836 0.9238795 0 0.3826828 0.9238798 0 0.3826838 0.9238795 0 0.3826826 0.9238799 0 0.3826832 0.9238796 -7.39096e-7 0.3826828 0.9238798 1.22557e-7 1 0 0 1 0 0 0.7071068 0 0.7071068 0.7071068 0 0.7071068 0.7071068 0 -0.7071068 0.7071068 0 -0.7071068 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 -0.9876863 0 0.1564474 -0.8909991 0 0.4540053 -0.7071458 0 0.7070678 -0.4539737 0 0.8910151 -0.1563833 0 0.9876965 0.1563833 0 0.9876965 0.4539737 0 0.8910151 0.7071458 0 0.7070678 0.8909991 0 0.4540053 0.9876863 0 0.1564474 0.9876863 0 -0.1564474 0.8909991 0 -0.4540053 0.7071458 0 -0.7070678 0.4539737 0 -0.8910151 0.1563833 0 -0.9876965 -0.1563833 0 -0.9876965 -0.4539737 0 -0.8910151 -0.7071458 0 -0.7070678 -0.8909991 0 -0.4540053 -0.9876863 0 -0.1564474 -0.9876863 0 -0.1564474 -0.8909991 0 -0.4540053 -0.7071458 0 -0.7070678 -0.4539737 0 -0.8910151 -0.1563833 0 -0.9876965 0.1563833 0 -0.9876965 0.4539737 0 -0.8910151 0.7071458 0 -0.7070678 0.8909991 0 -0.4540053 0.9876863 0 -0.1564474 0.9876863 0 0.1564474 0.8909991 0 0.4540053 0.7071458 0 0.7070678 0.4539737 0 0.8910151 0.1563833 0 0.9876965 -0.1563833 0 0.9876965 -0.4539737 0 0.8910151 -0.7071458 0 0.7070678 -0.8909991 0 0.4540053 -0.9876863 0 0.1564474 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 -0.9876863 0 0.1564474 -0.8909991 0 0.4540053 -0.7071458 0 0.7070678 -0.4539737 0 0.8910151 -0.1563833 0 0.9876965 0.1563833 0 0.9876965 0.4539737 0 0.8910151 0.7071458 0 0.7070678 0.8909991 0 0.4540053 0.9876863 0 0.1564474 0.9876863 0 -0.1564474 0.8909991 0 -0.4540053 0.7071458 0 -0.7070678 0.4539737 0 -0.8910151 0.1563833 0 -0.9876965 -0.1563833 0 -0.9876965 -0.4539737 0 -0.8910151 -0.7071458 0 -0.7070678 -0.8909991 0 -0.4540053 -0.9876863 0 -0.1564474 -0.9876863 0 -0.1564474 -0.8909991 0 -0.4540053 -0.7071458 0 -0.7070678 -0.4539737 0 -0.8910151 -0.1563833 0 -0.9876965 0.1563833 0 -0.9876965 0.4539737 0 -0.8910151 0.7071458 0 -0.7070678 0.8909991 0 -0.4540053 0.9876863 0 -0.1564474 0.9876863 0 0.1564474 0.8909991 0 0.4540053 0.7071458 0 0.7070678 0.4539737 0 0.8910151 0.1563833 0 0.9876965 -0.1563833 0 0.9876965 -0.4539737 0 0.8910151 -0.7071458 0 0.7070678 -0.8909991 0 0.4540053 -0.9876863 0 0.1564474 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 -0.1908095 0 0.9816271 -0.1908169 5.31761e-6 0.9816256 -0.1908041 0 0.9816282 -0.1908095 0 0.9816271 -0.1908095 0 0.9816271 -0.1908041 0 0.9816281 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 0 -1 0 0 -1 0 0.3826819 0 0.9238802 0.3826915 0 0.9238762 0.3826838 -1.64084e-6 0.9238794 0.3826819 0 0.9238801 0.1950889 0 0.9807855 0.1950889 0 0.9807855 0 0 1 0 0 1 -0.3826816 0 0.9238802 -0.3826816 0 0.9238802 -0.7071079 0 0.7071056 -0.7071079 0 0.7071056 -0.9238798 0 0.3826828 -0.9238798 0 0.3826828 -1 0 0 -1 0 0 -0.9238798 0 -0.3826828 -0.9238798 0 -0.3826828 -0.7071079 0 -0.7071056 -0.7071079 0 -0.7071056 -0.3826816 0 -0.9238802 -0.3826816 0 -0.9238802 0 0 -1 0 0 -1 0.1950913 0 -0.980785 0.1950913 0 -0.980785 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 -0.0333935 0.0231027 0.9991752 -0.06678241 -0.02313423 0.9974993 -0.1662983 0.0230683 0.9858056 -0.1991283 -0.02311593 0.9797008 -0.2962018 0.0231058 0.9548459 -0.3279277 -0.02308076 0.9444208 -0.4208098 0.02313953 0.9068538 -0.450898 -0.02310097 0.8922765 -0.5379306 0.02311515 0.8426721 -0.5657997 -0.02311319 0.8242188 -0.6454575 0.02308553 0.7634472 -0.6705996 -0.02310895 0.7414595 -0.7414702 0.0230875 0.6705884 -0.7634499 -0.02309137 0.6454542 -0.8242246 0.0230996 0.5657917 -0.8426678 -0.02310353 0.5379379 -0.8922809 0.02311903 0.4508883 -0.9068519 -0.02309811 0.4208161 -0.9444171 0.02309495 0.3279373 -0.9548447 -0.02309978 0.296206 -0.9796983 0.02311027 0.1991413 -0.9858077 -0.02311998 0.1662784 -0.9975012 0.0230903 0.06676954 -0.9991747 -0.02311247 0.03340464 -0.9975011 0.02309358 -0.06676948 -0.9947121 -0.02311956 -0.100067 -0.9796986 0.02309608 -0.1991413 -0.9725008 -0.02309143 -0.231752 -0.9444163 0.02313399 -0.327937 -0.932927 -0.02309226 -0.3593243 -0.8922813 0.02309703 -0.4508885 -0.8767184 -0.02310693 -0.4804487 -0.8242163 0.0230996 -0.5658037 -0.8048578 -0.02309066 -0.5930183 -0.7414609 0.02312022 -0.6705976 -0.718636 -0.02309536 -0.6950027 -0.645457 0.02312278 -0.7634466 -0.619575 -0.02310538 -0.7845973 -0.5379388 0.02310198 -0.8426673 -0.5094804 -0.02310675 -0.8601719 -0.4208102 0.0230953 -0.9068546 -0.3902831 -0.02309864 -0.9204051 -0.2962019 0.02309852 -0.954846 -0.264136 -0.02310198 -0.9642088 -0.1662981 0.02311646 -0.9858046 -0.133247 -0.02311652 -0.9908132 -0.0333935 0.02310192 -0.9991752 0 -0.02308952 -0.9997334 0.1000765 0.02310603 -0.9947113 0.1332454 -0.02308404 -0.9908143 0.2317454 0.02313548 -0.9725013 0.2641392 -0.02311164 -0.9642077 0.3592829 0.02311712 -0.9329424 0.3902828 -0.0231319 -0.9204044 0.4804399 0.02310252 -0.8767234 0.5094745 -0.02311748 -0.8601751 0.5930322 0.02310979 -0.8048471 0.6195819 -0.02307546 -0.7845928 0.6950019 0.02313035 -0.7186357 0.718636 -0.02309525 -0.6950027 0.7845984 0.02309632 -0.619574 0.8048576 -0.02309995 -0.5930181 0.8601751 0.02308958 -0.5094758 0.8767181 -0.0231195 -0.4804486 0.9204031 0.02309757 -0.3902879 0.932927 -0.02309638 -0.3593242 0.9642149 0.02310436 -0.2641133 0.9725006 -0.02309697 -0.231752 0.9908127 0.02309989 -0.1332544 0.9947121 -0.02311682 -0.100067 0.9997333 0.02308952 0 0.9991745 -0.02311736 0.03340464 0.9908127 0.02309989 0.1332544 0.9858083 -0.02309697 0.1662785 0.9642103 0.02310436 0.2641298 0.9548485 -0.02309429 0.296194 0.920408 0.02312004 0.390275 0.9068465 -0.02311068 0.4208269 0.860166 0.02308958 0.5094914 0.8426679 -0.02310049 0.5379379 0.7845848 0.02309632 0.6195911 0.7634497 -0.02309828 0.6454541 0.6949936 0.0230953 0.7186449 0.6705998 -0.02309876 0.7414596 0.5930323 0.0230953 0.8048473 0.5657995 -0.02312612 0.8242185 0.480467 0.02310252 0.8767085 0.4508979 -0.02311515 0.8922763 0.3593136 0.02311712 0.9329305 0.3279275 -0.02310907 0.9444202 0.2317417 0.02308237 0.9725036 0.1991283 -0.02310949 0.9797009 0.1000765 0.02310848 0.9947113 0.06678241 -0.02310001 0.9975001 -0.03338354 0.0231027 0.9991755 0.1000437 0.02310848 0.9947147 0.2317833 0.02308237 0.9724936 0.3592737 0.02311712 0.9329459 0.4804164 0.02310252 0.8767362 0.5930445 0.0230953 0.8048385 0.6950294 0.0230953 0.7186104 0.7846096 0.02309632 0.6195597 0.8601818 0.02308958 0.5094646 0.9203975 0.02312004 0.3902998 0.9642171 0.02310436 0.2641052 0.9908106 0.02309989 0.1332703 0.9997335 0.02308952 0 0.9908106 0.02309989 -0.1332703 0.9642036 0.02310436 -0.2641545 0.9204141 0.02309757 -0.3902619 0.8601543 0.02308958 -0.5095111 0.7845689 0.02309632 -0.6196113 0.6950023 0.02313035 -0.7186354 0.5930442 0.02310979 -0.8048382 0.4804979 0.02310252 -0.8766915 0.359366 0.02311712 -0.9329104 0.231771 0.02313548 -0.9724953 0.1000437 0.02310603 -0.9947148 -0.03338354 0.02310192 -0.9991756 -0.1662795 0.0231164 -0.9858077 -0.2962185 0.02309852 -0.9548409 -0.420834 0.0230953 -0.9068437 -0.5379351 0.02310198 -0.8426697 -0.645444 0.02312278 -0.7634575 -0.7414543 0.02312022 -0.6706049 -0.824227 0.0230996 -0.5657883 -0.8922943 0.02309703 -0.450863 -0.9444077 0.02313399 -0.327962 -0.9796987 0.02309608 -0.1991404 -0.9975011 0.02309358 -0.06676852 -0.9975012 0.0230903 0.06676852 -0.9796984 0.02311027 0.1991403 -0.9444084 0.02309495 0.3279623 -0.8922939 0.02311903 0.4508627 -0.8242022 0.0230996 0.5658243 -0.7414285 0.0230875 0.6706346 -0.6454446 0.02308553 0.7634581 -0.537959 0.02311515 0.8426541 -0.4208335 0.02313953 0.9068428 -0.2962184 0.0231058 0.9548407 -0.1662797 0.0230683 0.9858088 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 -0.1908095 0 -0.9816271 -0.1908095 0 -0.9816271 -0.1908095 0 -0.9816271 -0.1908118 0 -0.9816266 -0.1908118 0 -0.9816266 -0.1908063 -2.24451e-6 -0.9816277 -1 0 0 -1 0 0 -1 0 0 -1 0 0 0.3826838 -1.64084e-6 -0.9238794 0.3826819 0 -0.9238801 0.3826819 0 -0.9238802 0.3826915 0 -0.9238762 0 -1 0 0 -1 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 0.7071068 0 -0.7071068 0.7071068 0 -0.7071068 0.7071068 0 -0.7071068 0.7071068 0 -0.7071068 0.7071101 -3.35633e-6 0.7071036 0.7071266 0 0.7070869 0.7071267 0 0.7070869 0.7071068 0 0.7071068 0 1 0 0 1 0 0 1 0 0 1 0 1 0 0 1 0 0 0.9238798 0 0.3826828 0.9238798 0 0.3826828 0.9238798 0 -0.3826828 0.9238798 0 -0.3826828 0 -0.05708009 0.9983696 0 -0.1705201 0.9853543 0.002798318 -0.2817307 0.9594895 0 -0.2328113 0.9725219 0 -0.3892739 0.921122 0 -0.4917311 0.8707471 0 -0.5877912 0.8090127 0 -0.6761671 0.7367484 0 -0.7557493 0.6548609 0 -0.825474 0.5644403 0 -0.8844316 0.46667 0 -0.9318652 0.362805 0 -0.9671467 0.2542188 0 -0.9898217 0.1423134 0 -0.9995922 0.02855664 0 -0.9963319 -0.08557474 0 -0.9800827 -0.1985898 0 -0.9510559 -0.3090189 0 -0.9096324 -0.415414 0 -0.8563518 -0.5163929 0 -0.7919001 -0.6106507 0 -0.7171285 -0.6969409 0 -0.6330126 -0.7741415 0 -0.5406404 -0.8412538 0 -0.4412226 -0.8973978 0 -0.336064 -0.9418391 0.0066877 -0.2264921 -0.97399 0 -0.2604023 -0.9655002 0 -0.1139802 -0.9934831 0 0 -1 0 0.1139802 -0.9934831 0 0.2048636 -0.9787905 0.0066877 0.2264921 -0.97399 0 0.336064 -0.9418391 0 0.4412226 -0.8973978 0 0.5406404 -0.8412538 0 0.6330126 -0.7741415 0 0.7171285 -0.6969409 0 0.7919001 -0.6106507 0 0.8563518 -0.5163929 0 0.9096324 -0.415414 0 0.9510559 -0.3090189 0 0.9800827 -0.1985898 0 0.9963319 -0.08557474 0 0.9995922 0.02855664 0 0.9898217 0.1423134 0 0.9671467 0.2542188 0 0.9318652 0.362805 0 0.8844316 0.46667 0 0.825474 0.5644403 0 0.7557489 0.6548613 0 0.6761674 0.736748 0 0.5877912 0.8090127 0 0.4917311 0.8707471 0 0.3892739 0.921122 0 0.2878586 0.957673 0.002798318 0.2817307 0.9594895 0 0.1705201 0.9853542 0 0.05708009 0.9983695 0 0.05708009 0.9983695 0 0.1705201 0.9853542 0 0.2328113 0.9725219 0 0.3892739 0.921122 0 0.4917311 0.8707471 0 0.5877912 0.8090127 0 0.6761674 0.736748 0 0.7557489 0.6548613 0 0.825474 0.5644403 0 0.8844316 0.46667 0 0.9318652 0.362805 0 0.9671467 0.2542188 0 0.9898217 0.1423134 0 0.9995922 0.02855664 0 0.9963319 -0.08557474 0 0.9800827 -0.1985898 0 0.9510559 -0.3090189 0 0.9096324 -0.415414 0 0.8563518 -0.5163929 0 0.7919001 -0.6106507 0 0.7171285 -0.6969409 0 0.6330126 -0.7741415 0 0.5406404 -0.8412538 0 0.4412226 -0.8973978 0 0.336064 -0.9418391 0 0.2604023 -0.9655002 0 0.1139802 -0.9934831 0 0 -1 0 -0.1139802 -0.9934831 0 -0.2048636 -0.9787905 0 -0.336064 -0.9418391 0 -0.4412226 -0.8973978 0 -0.5406404 -0.8412538 0 -0.6330126 -0.7741415 0 -0.7171285 -0.6969409 0 -0.7919001 -0.6106507 0 -0.8563518 -0.5163929 0 -0.9096324 -0.415414 0 -0.9510559 -0.3090189 0 -0.9800827 -0.1985898 0 -0.9963319 -0.08557474 0 -0.9995922 0.02855664 0 -0.9898217 0.1423134 0 -0.9671467 0.2542188 0 -0.9318652 0.362805 0 -0.8844316 0.46667 0 -0.825474 0.5644403 0 -0.7557493 0.6548609 0 -0.6761671 0.7367484 0 -0.5877912 0.8090127 0 -0.4917311 0.8707471 0 -0.3892739 0.921122 0 -0.2878586 0.957673 0 -0.1705201 0.9853543 0 -0.05708009 0.9983696 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 0 -0.06406748 0.9979455 0 -0.1911608 0.9815587 0 -0.3151047 0.9490569 0 -0.4338894 0.9009661 0 -0.5455198 0.8380979 0 -0.6482381 0.7614377 0 -0.7402799 0.6722989 0 -0.8201735 0.572115 0 -0.886595 0.4625465 0 -0.9384699 0.3453611 0 -0.974928 0.2225202 0 -0.995379 0.09602469 0 -0.9994862 -0.03205078 0 -0.9871816 -0.1596009 0 -0.9586685 -0.2845253 0 -0.9144101 -0.404789 0 -0.8551464 -0.5183867 0 -0.7818354 -0.6234848 0 -0.6956777 -0.718354 0 -0.598103 -0.8014193 0 -0.490718 -0.8713184 0 -0.3752825 -0.9269105 0 -0.2536535 -0.9672952 0 -0.1278809 -0.9917896 0 0.03204268 -0.9994865 0 -0.03204268 -0.9994865 0 -0.03204268 -0.9994865 0 0.1278808 -0.9917895 0 0.2536535 -0.9672952 0 0.3752825 -0.9269105 0 0.490718 -0.8713184 0 0.598103 -0.8014193 0 0.6956777 -0.718354 0 0.7818354 -0.6234848 0 0.8551464 -0.5183867 0 0.9144101 -0.404789 0 0.9586685 -0.2845253 0 0.9871816 -0.1596009 0 0.9994862 -0.03205078 0 0.995379 0.09602469 0 0.974928 0.2225202 0 0.9384699 0.3453611 0 0.886595 0.4625465 0 0.8201735 0.572115 0 0.7402796 0.672299 0 0.6482381 0.7614377 0 0.5455201 0.8380978 0 0.4338894 0.9009661 0 0.3151047 0.9490569 0 0.1911608 0.9815587 0 0.06406748 0.9979455 0 0.06406748 0.9979455 0 0.1911608 0.9815587 0 0.3151047 0.9490569 0 0.4338894 0.9009661 0 0.5455201 0.8380978 0 0.6482381 0.7614377 0 0.7402796 0.672299 0 0.8201735 0.572115 0 0.886595 0.4625465 0 0.9384699 0.3453611 0 0.974928 0.2225202 0 0.995379 0.09602469 0 0.9994862 -0.03205078 0 0.9871816 -0.1596009 0 0.9586685 -0.2845253 0 0.9144101 -0.404789 0 0.8551464 -0.5183867 0 0.7818354 -0.6234848 0 0.6956777 -0.718354 0 0.598103 -0.8014193 0 0.490718 -0.8713184 0 0.3752825 -0.9269105 0 0.2536535 -0.9672952 0 0.1278808 -0.9917895 0 0.03204268 -0.9994865 0 -0.1278809 -0.9917896 0 -0.2536535 -0.9672952 0 -0.3752825 -0.9269105 0 -0.490718 -0.8713184 0 -0.598103 -0.8014193 0 -0.6956777 -0.718354 0 -0.7818354 -0.6234848 0 -0.8551464 -0.5183867 0 -0.9144101 -0.404789 0 -0.9586685 -0.2845253 0 -0.9871816 -0.1596009 0 -0.9994862 -0.03205078 0 -0.995379 0.09602469 0 -0.974928 0.2225202 0 -0.9384699 0.3453611 0 -0.886595 0.4625465 0 -0.8201735 0.572115 0 -0.7402799 0.6722989 0 -0.6482381 0.7614377 0 -0.5455198 0.8380979 0 -0.4338894 0.9009661 0 -0.3151047 0.9490569 0 -0.1911608 0.9815587 0 -0.06406748 0.9979455 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 -1 0 0 -1 0 0 1 0 0 1 0 0 0.9238798 0 0.3826828 0.9238799 0 0.3826828 0.9238799 0 -0.3826828 0.9238798 0 -0.3826828 0.3826789 0 -0.9238814 0.3826789 0 -0.9238814 0.1950913 0 -0.9807851 0.1950913 0 -0.980785 0.7071068 0 -0.7071068 0.7071068 0 -0.7071068 0.7071068 0 -0.7071068 0.7071068 0 -0.7071068 0.1020042 -0.8714453 -0.4797689 0.1020056 -0.8714465 -0.4797666 0.102005 -0.8714468 -0.4797661 0.1020057 -0.871452 -0.4797565 0 0 -1 0 0 -1 0 0 -1 0.3826789 0 0.9238814 0.3826789 0 0.9238814 0.1950913 0 0.980785 0.1950913 0 0.9807851 0.7071068 0 0.7071068 0.7071068 0 0.7071068 0.7071068 0 0.7071068 0.7071068 0 0.7071068 0.2588183 -0.965926 0 0.2588183 -0.965926 0 0.258818 -0.9659261 6.09127e-7 0.258818 -0.9659261 -6.09127e-7 0.2588163 -0.9659265 -3.33003e-6 0.2588163 -0.9659265 3.33003e-6 0.1020057 -0.871452 0.4797565 0.1020042 -0.8714453 0.4797689 0.1020056 -0.8714465 0.4797666 0.102005 -0.8714468 0.4797661 0 0 1 0 0 1 0 0 1 0.1200047 -0.9614024 -0.2475968 0.1200044 -0.9614024 -0.2475969 0.1200046 -0.9614025 -0.2475969 0.1200041 -0.9614027 -0.247596 0.1200046 -0.9614025 0.2475969 0.1200041 -0.9614027 0.247596 0.1200047 -0.9614024 0.2475968 0.1200044 -0.9614024 0.2475969 0.1305264 -0.9914448 0 0.1305257 -0.9914448 0 0.1305258 -0.991445 0 0.1305264 -0.9914448 0 0.06596523 -0.9892117 -0.1308012 0.06596487 -0.9892117 -0.130801 0.06596487 -0.9892117 0.130801 0.06596523 -0.9892117 0.1308012 -6.71317e-7 -0.9659262 -0.2588177 2.53133e-7 -0.9659258 -0.2588192 0 -0.9659258 -0.258819 0 -0.9659258 -0.258819 -0.3826828 0 -0.9238798 -0.3826828 0 -0.9238798 2.53133e-7 -0.9659258 0.2588192 0 -0.9659258 0.258819 -6.71317e-7 -0.9659262 0.2588177 0 -0.9659258 0.258819 -0.3826828 0 0.9238798 -0.3826828 0 0.9238798 -0.7071079 0 -0.7071056 -0.7071079 0 -0.7071056 -0.09904551 -0.9659259 -0.2391175 -0.09904742 -0.9659261 -0.239116 -0.7071079 0 0.7071056 -0.7071079 0 0.7071056 -0.09904742 -0.9659261 0.239116 -0.09904551 -0.9659259 0.2391175 -0.9238786 0 0.3826856 -0.9238786 0 0.3826856 -0.2391169 -0.9659258 0.09904921 -0.2391172 -0.9659259 0.09904623 -0.1830128 -0.9659259 0.1830122 -0.1830123 -0.965926 0.1830123 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 -0.9238786 0 -0.3826856 -0.9238786 0 -0.3826856 -0.1830123 -0.965926 -0.1830123 -0.1830128 -0.9659259 -0.1830122 -0.2391172 -0.9659259 -0.09904623 -0.2391169 -0.9659258 -0.09904921 -0.258819 -0.9659259 0 -0.258819 -0.9659258 0 + + + + + + + + + + + + + + + 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 +

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

+
+
+
+
+ + + + + 0.00100213 0 0 -0.93 0 0.001 0 0 0 0 0.001 -1.32 0 0 0 1 + + + + + + + + + + + + + +
diff --git a/kuka_kr16_support/meshes/kr16_2/visual/link_6.dae b/kuka_kr16_support/meshes/kr16_2/visual/link_6.dae new file mode 100644 index 000000000..92daff916 --- /dev/null +++ b/kuka_kr16_support/meshes/kr16_2/visual/link_6.dae @@ -0,0 +1,100 @@ + + + + + Blender User + Blender 2.74.0 commit date:2015-03-31, commit time:13:39, hash:000dfc0 + + 2015-06-09T10:53:57 + 2015-06-09T10:53:57 + + Z_UP + + + + + + + + + 0 0 0 1 + + + 0 0 0 1 + + + 0.00200704 0.00200704 0.00200704 1 + + + 0.0625 0.0625 0.0625 1 + + + 10 + + + 1 + + + + + + + + + + + + + + + + 1076 35.28825 1336.602 1076 38.92304 1317.548 1076 38.3092 1312.689 1076 37.0912 1307.945 1076 35.28825 1303.391 1076 38.92304 1322.446 1076 37.0912 1332.049 1076 -37.0912 1332.049 1076 -35.28825 1336.602 1076 -32.92879 1340.894 1076 -30.05002 1344.856 1076 -38.92304 1317.548 1076 -38.92304 1322.446 1076 -32.92879 1299.1 1076 -35.28825 1303.391 1076 32.92879 1299.1 1076 38.3092 1327.305 1076 -9.698906 1282.222 1076 -18.78839 1354.173 1076 -14.35686 1356.258 1076 -38.3092 1327.305 1076 -38.3092 1312.689 1076 -30.05002 1295.137 1076 -14.35686 1283.736 1076 26.69734 1348.427 1076 18.78839 1285.821 1076 14.35686 1283.736 1076 -22.92362 1351.549 1076 -37.0912 1307.945 1076 -22.92362 1288.445 1076 -26.69734 1291.567 1076 -18.78839 1285.821 1076 22.92362 1288.445 1076 30.05002 1295.137 1076 26.69734 1291.567 1076 32.92879 1340.894 1076 30.05002 1344.856 1076 9.698906 1282.222 1076 9.698906 1357.772 1076 14.35686 1356.258 1076 -26.69734 1348.427 1076 18.78839 1354.173 1076 0 1358.997 1076 4.887996 1358.689 1076 -9.698906 1357.772 1076 -4.887996 1358.689 1076 0 1280.997 1076 -4.887996 1281.304 1076 4.887996 1281.304 1076 22.92362 1351.549 1081.7 -4.887996 1358.689 1081.7 0 1358.997 1081.7 -9.698906 1357.772 1081.7 -14.35686 1356.258 1081.7 -18.78839 1354.173 1081.7 -22.92362 1351.549 1081.7 -26.69734 1348.427 1081.7 -30.05002 1344.856 1081.7 -32.92879 1340.894 1081.7 -35.28825 1336.602 1081.7 -37.0912 1332.049 1081.7 -38.3092 1327.305 1081.7 -38.92304 1322.446 1081.7 -38.92304 1317.548 1081.7 -38.3092 1312.689 1081.7 -37.0912 1307.945 1081.7 -35.28825 1303.391 1081.7 -32.92879 1299.1 1081.7 -30.05002 1295.137 1081.7 -26.69734 1291.567 1081.7 -22.92362 1288.445 1081.7 -18.78839 1285.821 1081.7 -14.35686 1283.736 1081.7 -9.698906 1282.222 1081.7 -4.887996 1281.304 1081.7 0 1280.997 1081.7 4.887996 1281.304 1081.7 9.698906 1282.222 1081.7 14.35686 1283.736 1081.7 18.78839 1285.821 1081.7 22.92362 1288.445 1081.7 26.69734 1291.567 1081.7 30.05002 1295.137 1081.7 32.92879 1299.1 1081.7 35.28825 1303.391 1081.7 37.0912 1307.945 1081.7 38.3092 1312.689 1081.7 38.92304 1317.548 1081.7 38.92304 1322.446 1081.7 38.3092 1327.305 1081.7 37.0912 1332.049 1081.7 35.28825 1336.602 1081.7 32.92879 1340.894 1081.7 30.05002 1344.856 1081.7 26.69734 1348.427 1081.7 22.92362 1351.549 1081.7 18.78839 1354.173 1081.7 14.35686 1356.258 1081.7 9.698906 1357.772 1081.7 4.887996 1358.689 1081.7 31.32744 1316.704 1081.7 31.48081 1321.096 1081.7 31.02145 1325.467 1081.7 -31.48081 1321.096 1081.7 -31.02145 1325.467 1081.7 -31.32744 1316.704 1081.7 30.56432 1312.376 1081.7 29.20629 1308.197 1081.7 29.95828 1329.731 1081.7 -30.56432 1312.376 1081.7 -29.20629 1308.197 1081.7 24.82234 1300.604 1081.7 21.88174 1297.338 1081.7 27.2798 1304.247 1081.7 28.31201 1333.806 1081.7 26.11468 1337.611 1081.7 -29.95828 1329.731 1081.7 -23.40906 1341.074 1081.7 -26.11468 1337.611 1081.7 -27.2798 1304.247 1081.7 -24.82234 1300.604 1081.7 23.40906 1341.074 1081.7 20.24781 1344.127 1081.7 -28.31201 1333.806 1081.7 16.69246 1346.71 1081.7 -20.24781 1344.127 1081.7 -16.69246 1346.71 1081.7 10.77363 1290.396 1081.7 14.78835 1292.184 1081.7 18.51524 1294.513 1081.7 -8.682578 1350.277 1081.7 -4.383953 1351.19 1081.7 -12.8122 1348.774 1081.7 -21.88174 1297.338 1081.7 -18.51524 1294.513 1081.7 12.8122 1348.774 1081.7 8.682577 1350.277 1081.7 4.383953 1351.19 1081.7 0 1351.497 1081.7 -10.77363 1290.396 1081.7 -14.78835 1292.184 1081.7 -6.549218 1289.185 1081.7 2.197329 1288.574 1081.7 6.549218 1289.185 1081.7 -2.197329 1288.574 1081.7 0 1288.497 1088 -4.383953 1351.19 1088 0 1351.497 1088 -8.682578 1350.277 1088 -12.8122 1348.774 1088 -8.838835 1350.22 1088 -16.69246 1346.71 1088 -20.24781 1344.127 1088 -23.13856 1341.336 1088 -21.33884 1343.074 1088 -23.40906 1341.074 1088 -26.11468 1337.611 1088 -28.31201 1333.806 1088 -29.95828 1329.731 1088 -31.02145 1325.467 1088 -30.18148 1328.836 1088 -31.48081 1321.096 1088 -31.32744 1316.704 1088 -30.56432 1312.376 1088 -29.20629 1308.197 1088 -30.16847 1311.158 1088 -27.2798 1304.247 1088 -24.82234 1300.604 1088 -23.07061 1298.658 1088 -21.88174 1297.338 1088 -18.51524 1294.513 1088 -21.33884 1296.882 1088 -14.78835 1292.184 1088 -10.88665 1290.447 1088 -10.77363 1290.396 1088 -6.549218 1289.185 1088 -8.838835 1289.842 1088 -2.197329 1288.574 1088 2.197329 1288.574 1088 0 1288.497 1088 6.549218 1289.185 1088 8.838835 1289.842 1088 10.77363 1290.396 1088 14.78835 1292.184 1088 10.88665 1290.447 1088 18.51524 1294.513 1088 21.33884 1296.882 1088 21.88174 1297.338 1088 24.82234 1300.604 1088 23.07061 1298.658 1088 27.2798 1304.247 1088 29.20629 1308.197 1088 30.16847 1311.158 1088 29.55 1309.255 1088 30.56432 1312.376 1088 31.32744 1316.704 1088 31.48081 1321.096 1088 31.02145 1325.467 1088 30.18148 1328.836 1088 29.95828 1329.731 1088 28.31201 1333.806 1088 29.55 1330.741 1088 26.11468 1337.611 1088 23.40906 1341.074 1088 21.33884 1343.074 1088 23.13856 1341.336 1088 20.24781 1344.127 1088 16.69246 1346.71 1088 12.8122 1348.774 1088 8.838835 1350.22 1088 8.682577 1350.277 1088 4.383953 1351.19 1088 29.55 1311.158 1088 29.55 1328.836 1088 27.6 1319.997 1088 21.33884 1311.158 1088 22.52725 1319.193 1088 22.4 1319.997 1088 27.47275 1319.193 1088 27.10345 1318.469 1088 27.47275 1320.8 1088 21.33884 1328.836 1088 25 1322.597 1088 22.52725 1320.8 1088 22.89656 1321.525 1088 26.52824 1322.1 1088 27.10345 1321.525 1088 25.80344 1322.47 1088 23.47176 1322.1 1088 24.19656 1322.47 1088 23.47176 1317.893 1088 22.89656 1318.469 1088 25 1317.397 1088 24.19656 1317.524 1088 25.80344 1317.524 1088 26.52824 1317.893 1088 8.838835 1311.158 1088 8.838835 1298.658 1088 15.10968 1302.726 1088 15.36105 1303.5 1088 21.33884 1298.658 1088 20.24566 1301.912 1088 19.99429 1301.139 1088 20.24566 1302.726 1088 15.10968 1301.912 1088 16.49729 1300.003 1088 15.83919 1300.481 1088 19.51615 1304.158 1088 19.99429 1303.5 1088 16.49729 1304.636 1088 17.27094 1304.887 1088 15.83919 1304.158 1088 17.27094 1299.751 1088 18.0844 1299.751 1088 19.51615 1300.481 1088 18.85805 1304.636 1088 15.36105 1301.139 1088 18.0844 1304.887 1088 18.85805 1300.003 1088 8.838835 1328.836 1088 21.33884 1341.336 1088 20.24566 1338.081 1088 20.24566 1337.268 1088 19.51615 1339.513 1088 19.99429 1338.855 1088 19.99429 1336.494 1088 18.0844 1340.243 1088 18.85805 1339.991 1088 8.838835 1341.336 1088 17.27094 1340.243 1088 15.83919 1339.513 1088 16.49729 1339.991 1088 15.36105 1336.494 1088 15.10968 1337.268 1088 15.83919 1335.836 1088 17.27094 1335.107 1088 16.49729 1335.358 1088 19.51615 1335.836 1088 15.36105 1338.855 1088 15.10968 1338.081 1088 18.85805 1335.358 1088 18.0844 1335.107 1088 -8.838835 1290.447 1088 -2.472747 1294.193 1088 -2.6 1294.997 1088 -8.838835 1298.658 1088 -1.528242 1292.893 1088 -2.103444 1293.469 1088 8.838835 1290.447 1088 2.6 1294.997 1088 -0.8034443 1297.47 1088 0 1297.597 1088 -2.472747 1295.8 1088 -2.103444 1296.525 1088 0 1292.397 1088 2.472747 1295.8 1088 1.528242 1297.1 1088 2.103444 1296.525 1088 0.8034441 1297.47 1088 -1.528242 1297.1 1088 -0.8034443 1292.524 1088 2.472747 1294.193 1088 2.103444 1293.469 1088 1.528242 1292.893 1088 0.8034441 1292.524 1088 -8.838835 1311.158 1088 -8.838835 1328.836 1088 -8.838835 1341.336 1088 -21.33884 1298.658 1088 -20.24566 1301.912 1088 -20.24566 1302.726 1088 -19.51615 1300.481 1088 -19.99429 1301.139 1088 -15.36105 1303.5 1088 -15.10968 1302.726 1088 -21.33884 1311.158 1088 -19.99429 1303.5 1088 -15.10968 1301.912 1088 -15.83919 1304.158 1088 -17.27094 1304.887 1088 -18.0844 1299.751 1088 -18.85805 1300.003 1088 -16.49729 1304.636 1088 -17.27094 1299.751 1088 -18.85805 1304.636 1088 -18.0844 1304.887 1088 -15.83919 1300.481 1088 -16.49729 1300.003 1088 -19.51615 1304.158 1088 -15.36105 1301.139 1088 -21.33884 1328.836 1088 -15.10968 1337.268 1088 -15.36105 1336.494 1088 -15.10968 1338.081 1088 -16.49729 1339.991 1088 -15.83919 1339.513 1088 -21.33884 1341.336 1088 -18.0844 1340.243 1088 -17.27094 1340.243 1088 -20.24566 1338.081 1088 -19.99429 1338.855 1088 -20.24566 1337.268 1088 -15.83919 1335.836 1088 -18.85805 1339.991 1088 -15.36105 1338.855 1088 -19.51615 1339.513 1088 -19.51615 1335.836 1088 -19.99429 1336.494 1088 -16.49729 1335.358 1088 -17.27094 1335.107 1088 -18.85805 1335.358 1088 -18.0844 1335.107 1088 2.472747 1345.8 1088 2.6 1344.997 1088 2.103444 1346.525 1088 1.528242 1347.1 1088 0 1347.597 1088 0.8034441 1347.47 1088 -0.8034443 1347.47 1088 -2.103444 1346.525 1088 -1.528242 1347.1 1088 -2.472747 1345.8 1088 -2.6 1344.997 1088 2.472747 1344.193 1088 2.103444 1343.469 1088 -2.472747 1344.193 1088 0.8034441 1342.524 1088 0 1342.397 1088 -1.528242 1342.893 1088 -2.103444 1343.469 1088 1.528242 1342.893 1088 -0.8034443 1342.524 1088 -26.52824 1322.1 1088 -27.47275 1320.8 1088 -27.47275 1319.193 1088 -27.6 1319.997 1088 -22.52725 1320.8 1088 -22.4 1319.997 1088 -27.10345 1321.525 1088 -26.52824 1317.893 1088 -27.10345 1318.469 1088 -22.52725 1319.193 1088 -22.89656 1318.469 1088 -25.80344 1322.47 1088 -25 1322.597 1088 -25.80344 1317.524 1088 -25 1317.397 1088 -23.47176 1322.1 1088 -22.89656 1321.525 1088 -24.19656 1322.47 1088 -23.47176 1317.893 1088 -24.19656 1317.524 1078 25.80344 1317.524 1078 25 1317.397 1078 26.52824 1317.893 1078 27.10345 1318.469 1078 27.47275 1319.193 1078 27.6 1319.997 1078 27.47275 1320.8 1078 27.10345 1321.525 1078 26.52824 1322.1 1078 25.80344 1322.47 1078 25 1322.597 1078 24.19656 1322.47 1078 23.47176 1322.1 1078 22.89656 1321.525 1078 22.52725 1320.8 1078 22.4 1319.997 1078 22.52725 1319.193 1078 22.89656 1318.469 1078 23.47176 1317.893 1078 24.19656 1317.524 1078 19.99429 1336.494 1078 19.51615 1335.836 1078 20.24566 1337.268 1078 20.24566 1338.081 1078 19.99429 1338.855 1078 19.51615 1339.513 1078 18.85805 1339.991 1078 18.0844 1340.243 1078 17.27094 1340.243 1078 16.49729 1339.991 1078 15.83919 1339.513 1078 15.36105 1338.855 1078 15.10968 1338.081 1078 15.10968 1337.268 1078 15.36105 1336.494 1078 15.83919 1335.836 1078 16.49729 1335.358 1078 17.27094 1335.107 1078 18.0844 1335.107 1078 18.85805 1335.358 1078 2.472747 1345.8 1078 2.6 1344.997 1078 2.103444 1346.525 1078 1.528242 1347.1 1078 0.8034441 1347.47 1078 0 1347.597 1078 -0.8034443 1347.47 1078 -1.528242 1347.1 1078 -2.103444 1346.525 1078 -2.472747 1345.8 1078 -2.6 1344.997 1078 -2.472747 1344.193 1078 -2.103444 1343.469 1078 -1.528242 1342.893 1078 -0.8034443 1342.524 1078 0 1342.397 1078 0.8034441 1342.524 1078 1.528242 1342.893 1078 2.103444 1343.469 1078 2.472747 1344.193 1078 -16.49729 1339.991 1078 -15.83919 1339.513 1078 -17.27094 1340.243 1078 -18.0844 1340.243 1078 -18.85805 1339.991 1078 -19.51615 1339.513 1078 -19.99429 1338.855 1078 -20.24566 1338.081 1078 -20.24566 1337.268 1078 -19.99429 1336.494 1078 -19.51615 1335.836 1078 -18.85805 1335.358 1078 -18.0844 1335.107 1078 -17.27094 1335.107 1078 -16.49729 1335.358 1078 -15.83919 1335.836 1078 -15.36105 1336.494 1078 -15.10968 1337.268 1078 -15.10968 1338.081 1078 -15.36105 1338.855 1078 -25.80344 1322.47 1078 -25 1322.597 1078 -26.52824 1322.1 1078 -27.10345 1321.525 1078 -27.47275 1320.8 1078 -27.6 1319.997 1078 -27.47275 1319.193 1078 -27.10345 1318.469 1078 -26.52824 1317.893 1078 -25.80344 1317.524 1078 -25 1317.397 1078 -24.19656 1317.524 1078 -23.47176 1317.893 1078 -22.89656 1318.469 1078 -22.52725 1319.193 1078 -22.4 1319.997 1078 -22.52725 1320.8 1078 -22.89656 1321.525 1078 -23.47176 1322.1 1078 -24.19656 1322.47 1078 -19.99429 1303.5 1078 -19.51615 1304.158 1078 -20.24566 1302.726 1078 -20.24566 1301.912 1078 -19.99429 1301.139 1078 -19.51615 1300.481 1078 -18.85805 1300.003 1078 -18.0844 1299.751 1078 -17.27094 1299.751 1078 -16.49729 1300.003 1078 -15.83919 1300.481 1078 -15.36105 1301.139 1078 -15.10968 1301.912 1078 -15.10968 1302.726 1078 -15.36105 1303.5 1078 -15.83919 1304.158 1078 -16.49729 1304.636 1078 -17.27094 1304.887 1078 -18.0844 1304.887 1078 -18.85805 1304.636 1078 -2.472747 1294.193 1078 -2.6 1294.997 1078 -2.103444 1293.469 1078 -1.528242 1292.893 1078 -0.8034443 1292.524 1078 0 1292.397 1078 0.8034441 1292.524 1078 1.528242 1292.893 1078 2.103444 1293.469 1078 2.472747 1294.193 1078 2.6 1294.997 1078 2.472747 1295.8 1078 2.103444 1296.525 1078 1.528242 1297.1 1078 0.8034441 1297.47 1078 0 1297.597 1078 -0.8034443 1297.47 1078 -1.528242 1297.1 1078 -2.103444 1296.525 1078 -2.472747 1295.8 1078 16.49729 1300.003 1078 15.83919 1300.481 1078 17.27094 1299.751 1078 18.0844 1299.751 1078 18.85805 1300.003 1078 19.51615 1300.481 1078 19.99429 1301.139 1078 20.24566 1301.912 1078 20.24566 1302.726 1078 19.99429 1303.5 1078 19.51615 1304.158 1078 18.85805 1304.636 1078 18.0844 1304.887 1078 17.27094 1304.887 1078 16.49729 1304.636 1078 15.83919 1304.158 1078 15.36105 1303.5 1078 15.10968 1302.726 1078 15.10968 1301.912 1078 15.36105 1301.139 + + + + + + + + + + -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 0 -0.06278407 0.9980272 0 -0.1873802 0.9822875 0 -0.309011 0.9510584 0 -0.4257801 0.9048267 0 -0.5358225 0.8443307 0 -0.6374313 0.7705072 0 -0.728964 0.6845522 0 -0.8090161 0.5877865 0 -0.8763077 0.4817516 0 -0.9297758 0.3681263 0 -0.9685845 0.2486847 0 -0.9921146 0.1253337 0 -1 0 0 -0.9921146 -0.1253337 0 -0.9685829 -0.2486907 0 -0.9297758 -0.3681263 0 -0.8763077 -0.4817516 0 -0.8090161 -0.5877865 0 -0.728964 -0.6845522 0 -0.6374313 -0.7705072 0 -0.5358225 -0.8443307 0 -0.4257801 -0.9048267 0 -0.309011 -0.9510584 0 -0.1873802 -0.9822875 0 -0.06280893 -0.9980255 0 0.06280893 -0.9980255 0 0.1873802 -0.9822875 0 0.309011 -0.9510584 0 0.4257801 -0.9048267 0 0.5358225 -0.8443307 0 0.6374315 -0.770507 0 0.7289637 -0.6845523 0 0.8090165 -0.587786 0 0.8763075 -0.4817523 0 0.9297758 -0.3681263 0 0.9685829 -0.2486907 0 0.9921146 -0.1253337 0 1 0 0 0.9921146 0.1253337 0 0.9685845 0.2486847 0 0.9297758 0.3681263 0 0.8763075 0.4817523 0 0.8090165 0.587786 0 0.7289637 0.6845523 0 0.6374315 0.770507 0 0.5358225 0.8443307 0 0.4257801 0.9048267 0 0.309011 0.9510584 0 0.1873802 0.9822875 0 0.06278407 0.9980272 0 0.06278407 0.9980272 0 0.1873802 0.9822875 0 0.309011 0.9510584 0 0.4257801 0.9048267 0 0.5358225 0.8443307 0 0.6374315 0.770507 0 0.7289637 0.6845523 0 0.8090165 0.587786 0 0.8763075 0.4817523 0 0.9297758 0.3681263 0 0.9685845 0.2486847 0 0.9921146 0.1253337 0 1 0 0 0.9921146 -0.1253337 0 0.9685829 -0.2486907 0 0.9297758 -0.3681263 0 0.8763075 -0.4817523 0 0.8090165 -0.587786 0 0.7289637 -0.6845523 0 0.6374315 -0.770507 0 0.5358225 -0.8443307 0 0.4257801 -0.9048267 0 0.309011 -0.9510584 0 0.1873802 -0.9822875 0 0.06280893 -0.9980255 0 -0.06280893 -0.9980255 0 -0.1873802 -0.9822875 0 -0.309011 -0.9510584 0 -0.4257801 -0.9048267 0 -0.5358225 -0.8443307 0 -0.6374313 -0.7705072 0 -0.728964 -0.6845522 0 -0.8090161 -0.5877865 0 -0.8763077 -0.4817516 0 -0.9297758 -0.3681263 0 -0.9685829 -0.2486907 0 -0.9921146 -0.1253337 0 -1 0 0 -0.9921146 0.1253337 0 -0.9685845 0.2486847 0 -0.9297758 0.3681263 0 -0.8763077 0.4817516 0 -0.8090161 0.5877865 0 -0.728964 0.6845522 0 -0.6374313 0.7705072 0 -0.5358225 0.8443307 0 -0.4257801 0.9048267 0 -0.309011 0.9510584 0 -0.1873802 0.9822875 0 -0.06278407 0.9980272 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 0 -0.06974804 0.9975646 0 -0.2079107 0.9781478 0 -0.3420157 0.9396942 1.79009e-6 -0.3420182 0.9396933 0 -0.4694831 0.8829414 0 -0.5877692 0.8090286 0 -0.6946715 0.7193272 -2.96227e-6 -0.6946668 0.7193317 0 -0.6946716 0.719327 0 -0.7880085 0.6156643 0 -0.8660268 0.4999977 0 -0.9271815 0.3746124 0 -0.9702953 0.2419234 2.17219e-6 -0.9702963 0.2419195 0 -0.9945219 0.1045281 0 -0.9993909 -0.03489965 0 -0.9848077 -0.1736487 0 -0.9510575 -0.3090139 1.7438e-6 -0.9510564 -0.3090173 0 -0.8987967 -0.4383658 0 -0.8290356 -0.5591958 6.84602e-6 -0.7431451 -0.6691303 0 -0.7431613 -0.6691123 0 -0.6427847 -0.7660468 -1.98061e-6 -0.6427874 -0.7660447 0 -0.5299264 -0.8480437 1.40989e-5 -0.4067381 -0.9135448 0 -0.4073936 -0.9132527 0 -0.2756681 -0.9612529 1.4424e-5 -0.2756314 -0.9612634 0 -0.1391628 -0.9902696 0 0.03492212 -0.9993901 0 -0.03492212 -0.99939 0 -0.03492212 -0.99939 0 0.1391628 -0.9902695 1.4424e-5 0.2756314 -0.9612634 0 0.275588 -0.9612758 0 0.406719 -0.9135532 1.41608e-5 0.4067381 -0.9135448 0 0.5299264 -0.8480437 -1.98061e-6 0.6427874 -0.7660447 0 0.6428008 -0.7660334 0 0.743134 -0.6691426 6.84602e-6 0.7431451 -0.6691303 0 0.8290356 -0.5591958 0 0.8987967 -0.4383658 1.7438e-6 0.9510564 -0.3090173 1.91924e-6 0.9510563 -0.3090176 0 0.9510538 -0.3090255 0 0.9848077 -0.1736487 0 0.9993909 -0.03489923 0 0.994522 0.1045277 2.17219e-6 0.9702963 0.2419195 0 0.9702999 0.2419052 0 0.9271822 0.3746107 9.21428e-7 0.9271815 0.3746124 0 0.8660268 0.4999977 0 0.7880085 0.6156643 -2.96227e-6 0.6946668 0.7193317 0 0.6946715 0.7193272 0 0.6946581 0.7193402 0 0.5877692 0.8090286 0 0.4694831 0.8829414 1.74057e-6 0.3420181 0.9396934 0 0.3420801 0.9396709 0 0.2079107 0.9781478 0 0.06974804 0.9975646 0 0.06974804 0.9975646 0 0.2079107 0.9781478 0 0.3420157 0.9396942 0 0.4694831 0.8829414 0 0.5877692 0.8090286 0 0.6946716 0.719327 0 0.7880085 0.6156643 0 0.8660268 0.4999977 0 0.9271795 0.3746173 0 0.9702953 0.2419234 0 0.994522 0.1045277 0 0.9993909 -0.03489923 0 0.9848077 -0.1736487 0 0.9510596 -0.3090072 0 0.8987967 -0.4383658 0 0.8290356 -0.5591958 0 0.7431613 -0.6691123 0 0.6427847 -0.7660468 0 0.5299264 -0.8480437 0 0.4073966 -0.9132514 0 0.2756681 -0.9612529 0 0.1391628 -0.9902695 0 0.03492212 -0.9993901 0 -0.1391628 -0.9902696 0 -0.275588 -0.9612758 0 -0.4067191 -0.9135533 0 -0.5299264 -0.8480437 0 -0.6428008 -0.7660334 0 -0.743134 -0.6691426 0 -0.8290356 -0.5591958 0 -0.8987967 -0.4383658 0 -0.9510538 -0.3090255 0 -0.9848077 -0.1736487 0 -0.9993909 -0.03489965 0 -0.9945219 0.1045281 0 -0.9702999 0.2419052 0 -0.9271815 0.3746124 0 -0.8660268 0.4999977 0 -0.7880085 0.6156643 0 -0.6946581 0.7193402 0 -0.5877692 0.8090286 0 -0.4694831 0.8829414 0 -0.3420819 0.9396701 0 -0.2079107 0.9781478 0 -0.06974804 0.9975646 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 0 -0.156514 0.9876757 0 -0.4539511 0.8910267 0 -0.7071021 0.7071115 0 -0.8909898 0.4540233 0 -0.9876891 0.1564295 0 -0.9876891 -0.1564295 0 -0.8910207 -0.4539626 0 -0.7071021 -0.7071115 0 -0.4539511 -0.8910267 0 -0.1563676 -0.987699 0 0.1563676 -0.987699 0 0.4539511 -0.8910267 0 0.7071021 -0.7071115 0 0.8910207 -0.4539626 0 0.9876891 -0.1564295 0 0.9876891 0.1564295 0 0.8909898 0.4540233 0 0.7071021 0.7071115 0 0.4539511 0.8910267 0 0.156514 0.9876757 0 0.156514 0.9876757 0 0.4539511 0.8910267 0 0.7071021 0.7071115 0 0.8909898 0.4540233 0 0.9876891 0.1564295 0 0.9876891 -0.1564295 0 0.8910207 -0.4539626 0 0.7071021 -0.7071115 0 0.4539511 -0.8910267 0 0.1563676 -0.987699 0 -0.1563676 -0.987699 0 -0.4539511 -0.8910267 0 -0.7071021 -0.7071115 0 -0.8910207 -0.4539626 0 -0.9876891 -0.1564295 0 -0.9876891 0.1564295 0 -0.8909898 0.4540233 0 -0.7071021 0.7071115 0 -0.4539511 0.8910267 0 -0.156514 0.9876757 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 0 -0.8090088 0.5877966 0 -0.9510605 0.3090046 0 -1 0 0 -0.9510462 -0.3090487 0 -0.8090606 -0.5877252 0 -0.5876954 -0.8090824 0 -0.3091188 -0.9510234 0 0 -1 0 0.3091188 -0.9510234 0 0.5876954 -0.8090824 0 0.8090601 -0.5877261 0 0.9510466 -0.3090477 0 1 0 0 0.951061 0.3090036 0 0.8090082 0.5877974 0 0.5877935 0.8090109 0 0.3089831 0.9510676 0 0 1 0 -0.3089831 0.9510676 0 -0.5877935 0.8090109 0 -0.5877935 0.8090109 0 -0.3089831 0.9510676 0 0 1 0 0.3089831 0.9510676 0 0.5877935 0.8090109 0 0.8090082 0.5877974 0 0.951061 0.3090036 0 1 0 0 0.9510466 -0.3090477 0 0.8090601 -0.5877261 0 0.5876954 -0.8090824 0 0.3091188 -0.9510234 0 0 -1 0 -0.3091188 -0.9510234 0 -0.5876954 -0.8090824 0 -0.8090606 -0.5877252 0 -0.9510462 -0.3090487 0 -1 0 0 -0.9510605 0.3090046 0 -0.8090088 0.5877966 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 0 -0.9876891 -0.1564301 0 -0.8910207 -0.4539626 0 -0.7071024 -0.7071112 0 -0.4539514 -0.8910265 0 -0.1563675 -0.987699 0 0.1563675 -0.987699 0 0.4539514 -0.8910264 0 0.7071023 -0.7071112 0 0.8910207 -0.4539626 0 0.9876891 -0.1564301 0 0.9876891 0.1564301 0 0.8909898 0.4540233 0 0.7071023 0.7071112 0 0.4539514 0.8910264 0 0.1565139 0.9876757 0 -0.1565139 0.9876757 0 -0.4539514 0.8910265 0 -0.7071024 0.7071112 0 -0.8909898 0.4540233 0 -0.9876891 0.1564301 0 -0.9876891 0.1564301 0 -0.8909898 0.4540233 0 -0.7071024 0.7071112 0 -0.4539514 0.8910265 0 -0.1565139 0.9876757 0 0.1565139 0.9876757 0 0.4539514 0.8910264 0 0.7071023 0.7071112 0 0.8909898 0.4540233 0 0.9876891 0.1564301 0 0.9876891 -0.1564301 0 0.8910207 -0.4539626 0 0.7071023 -0.7071112 0 0.4539514 -0.8910264 0 0.1563675 -0.987699 0 -0.1563675 -0.987699 0 -0.4539514 -0.8910265 0 -0.7071024 -0.7071112 0 -0.8910207 -0.4539626 0 -0.9876891 -0.1564301 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 0 -0.5876958 -0.8090819 0 -0.3091188 -0.9510234 0 0 -1 0 0.3091188 -0.9510234 0 0.5876954 -0.8090824 0 0.8090596 -0.5877268 0 0.9510469 -0.3090466 0 1 0 0 0.9510613 0.3090025 0 0.8090077 0.5877981 0 0.5877935 0.8090109 0 0.3089831 0.9510676 0 0 1 0 -0.3089831 0.9510676 0 -0.5877941 0.8090106 0 -0.8090077 0.5877981 0 -0.951061 0.3090036 0 -1 0 0 -0.9510466 -0.3090477 0 -0.8090596 -0.5877268 0 -0.8090596 -0.5877268 0 -0.9510466 -0.3090477 0 -1 0 0 -0.951061 0.3090036 0 -0.8090077 0.5877981 0 -0.5877941 0.8090106 0 -0.3089831 0.9510676 0 0 1 0 0.3089831 0.9510676 0 0.5877935 0.8090109 0 0.8090077 0.5877981 0 0.9510613 0.3090025 0 1 0 0 0.9510469 -0.3090466 0 0.8090596 -0.5877268 0 0.5876954 -0.8090824 0 0.3091188 -0.9510234 0 0 -1 0 -0.3091188 -0.9510234 0 -0.5876958 -0.8090819 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 0 0.1563676 -0.987699 0 0.4539511 -0.8910267 0 0.7071021 -0.7071115 0 0.8910207 -0.4539626 0 0.9876891 -0.1564295 0 0.9876891 0.1564295 0 0.8909898 0.4540233 0 0.7071021 0.7071115 0 0.4539511 0.8910267 0 0.156514 0.9876757 0 -0.156514 0.9876757 0 -0.4539511 0.8910267 0 -0.7071021 0.7071115 0 -0.8909898 0.4540233 0 -0.9876891 0.1564295 0 -0.9876891 -0.1564295 0 -0.8910207 -0.4539626 0 -0.7071021 -0.7071115 0 -0.4539511 -0.8910267 0 -0.1563676 -0.987699 0 -0.1563676 -0.987699 0 -0.4539511 -0.8910267 0 -0.7071021 -0.7071115 0 -0.8910207 -0.4539626 0 -0.9876891 -0.1564295 0 -0.9876891 0.1564295 0 -0.8909898 0.4540233 0 -0.7071021 0.7071115 0 -0.4539511 0.8910267 0 -0.156514 0.9876757 0 0.156514 0.9876757 0 0.4539511 0.8910267 0 0.7071021 0.7071115 0 0.8909898 0.4540233 0 0.9876891 0.1564295 0 0.9876891 -0.1564295 0 0.8910207 -0.4539626 0 0.7071021 -0.7071115 0 0.4539511 -0.8910267 0 0.1563676 -0.987699 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 0 0.8090596 -0.5877268 0 0.9510469 -0.3090466 0 1 0 0 0.9510613 0.3090025 0 0.8090077 0.5877981 0 0.5877935 0.8090109 0 0.3089831 0.9510676 0 0 1 0 -0.3089831 0.9510676 0 -0.5877941 0.8090106 0 -0.8090077 0.5877981 0 -0.951061 0.3090036 0 -1 0 0 -0.9510466 -0.3090477 0 -0.8090596 -0.5877268 0 -0.5877941 -0.8090106 0 -0.3089831 -0.9510676 0 0 -1 0 0.3089831 -0.9510676 0 0.5877935 -0.8090109 0 0.5877935 -0.8090109 0 0.3089831 -0.9510676 0 0 -1 0 -0.3089831 -0.9510676 0 -0.5877941 -0.8090106 0 -0.8090596 -0.5877268 0 -0.9510466 -0.3090477 0 -1 0 0 -0.951061 0.3090036 0 -0.8090077 0.5877981 0 -0.5877941 0.8090106 0 -0.3089831 0.9510676 0 0 1 0 0.3089831 0.9510676 0 0.5877935 0.8090109 0 0.8090077 0.5877981 0 0.9510613 0.3090025 0 1 0 0 0.9510469 -0.3090466 0 0.8090596 -0.5877268 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 0 0.9876891 0.1564301 0 0.8909898 0.4540233 0 0.7071023 0.7071112 0 0.4539514 0.8910264 0 0.1565139 0.9876757 0 -0.1565139 0.9876757 0 -0.4539514 0.8910265 0 -0.7071024 0.7071112 0 -0.8909898 0.4540233 0 -0.9876891 0.1564301 0 -0.9876891 -0.1564301 0 -0.8910207 -0.4539626 0 -0.7071024 -0.7071112 0 -0.4539514 -0.8910265 0 -0.1563675 -0.987699 0 0.1563675 -0.987699 0 0.4539514 -0.8910264 0 0.7071023 -0.7071112 0 0.8910207 -0.4539626 0 0.9876891 -0.1564301 0 0.9876891 -0.1564301 0 0.8910207 -0.4539626 0 0.7071023 -0.7071112 0 0.4539514 -0.8910264 0 0.1563675 -0.987699 0 -0.1563675 -0.987699 0 -0.4539514 -0.8910265 0 -0.7071024 -0.7071112 0 -0.8910207 -0.4539626 0 -0.9876891 -0.1564301 0 -0.9876891 0.1564301 0 -0.8909898 0.4540233 0 -0.7071024 0.7071112 0 -0.4539514 0.8910265 0 -0.1565139 0.9876757 0 0.1565139 0.9876757 0 0.4539514 0.8910264 0 0.7071023 0.7071112 0 0.8909898 0.4540233 0 0.9876891 0.1564301 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 0 0.5877935 0.8090109 0 0.3089831 0.9510676 0 0 1 0 -0.3089831 0.9510676 0 -0.5877935 0.8090109 0 -0.8090088 0.5877966 0 -0.9510605 0.3090046 0 -1 0 0 -0.9510462 -0.3090487 0 -0.8090606 -0.5877252 0 -0.5877935 -0.8090109 0 -0.3089831 -0.9510676 0 0 -1 0 0.3089831 -0.9510676 0 0.5877935 -0.8090109 0 0.8090601 -0.5877261 0 0.9510466 -0.3090477 0 1 0 0 0.951061 0.3090036 0 0.8090082 0.5877974 0 0.8090082 0.5877974 0 0.951061 0.3090036 0 1 0 0 0.9510466 -0.3090477 0 0.8090601 -0.5877261 0 0.5877935 -0.8090109 0 0.3089831 -0.9510676 0 0 -1 0 -0.3089831 -0.9510676 0 -0.5877935 -0.8090109 0 -0.8090606 -0.5877252 0 -0.9510462 -0.3090487 0 -1 0 0 -0.9510605 0.3090046 0 -0.8090088 0.5877966 0 -0.5877935 0.8090109 0 -0.3089831 0.9510676 0 0 1 0 0.3089831 0.9510676 0 0.5877935 0.8090109 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 + + + + + + + + + + + + + + + 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 +

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

+
+
+
+
+ + + + + 0.001 0 0 -0.93 0 0.001 0 0 0 0 0.001 -1.32 0 0 0 1 + + + + + + + + + + + + + +
diff --git a/kuka_kr16_support/package.xml b/kuka_kr16_support/package.xml new file mode 100644 index 000000000..fcf9a147c --- /dev/null +++ b/kuka_kr16_support/package.xml @@ -0,0 +1,47 @@ + + + kuka_kr16_support + 0.1.0 + +

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

+

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

+

Specifications:

+
    +
  • KR 16-2 - Default
  • +
+

+ Joint limits and maximum joint velocities are based on the information + found in the online datasheet here. 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. +

+
+ Lars Tingelstad + Lars Tingelstad + G.A. vd. Hoorn (TU Delft Robotics Institute) + BSD + + http://wiki.ros.org/kuka_kr16_support + https://github.com/ros-industrial/kuka_experimental/issues + https://github.com/ros-industrial/kuka_experimental + + ament_cmake + + kuka_resources + + + ament_cmake + +
diff --git a/kuka_kr16_support/test/roslaunch_test.xml b/kuka_kr16_support/test/roslaunch_test.xml new file mode 100644 index 000000000..c7a70b290 --- /dev/null +++ b/kuka_kr16_support/test/roslaunch_test.xml @@ -0,0 +1,9 @@ + + + + + + + + + diff --git a/kuka_kr16_support/urdf/kr16_2.urdf b/kuka_kr16_support/urdf/kr16_2.urdf new file mode 100644 index 000000000..7a526d850 --- /dev/null +++ b/kuka_kr16_support/urdf/kr16_2.urdf @@ -0,0 +1,217 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/kuka_kr16_support/urdf/kr16_2.xacro b/kuka_kr16_support/urdf/kr16_2.xacro new file mode 100644 index 000000000..893a73044 --- /dev/null +++ b/kuka_kr16_support/urdf/kr16_2.xacro @@ -0,0 +1,6 @@ + + + + + + diff --git a/kuka_kr16_support/urdf/kr16_2_macro.xacro b/kuka_kr16_support/urdf/kr16_2_macro.xacro new file mode 100644 index 000000000..da876834e --- /dev/null +++ b/kuka_kr16_support/urdf/kr16_2_macro.xacro @@ -0,0 +1,225 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +